Refactored existing serialization functionality, added exposed interface for serialization
parent
2196953188
commit
19f7da62dd
72
.cproject
72
.cproject
|
@ -619,54 +619,6 @@
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
<runAllBuilders>true</runAllBuilders>
|
<runAllBuilders>true</runAllBuilders>
|
||||||
</target>
|
</target>
|
||||||
<target name="testPlanarSLAM.run" path="build/gtsam/slam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
|
||||||
<buildCommand>make</buildCommand>
|
|
||||||
<buildArguments>-j5</buildArguments>
|
|
||||||
<buildTarget>testPlanarSLAM.run</buildTarget>
|
|
||||||
<stopOnError>true</stopOnError>
|
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
|
||||||
<runAllBuilders>true</runAllBuilders>
|
|
||||||
</target>
|
|
||||||
<target name="testPose2SLAM.run" path="build/gtsam/slam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
|
||||||
<buildCommand>make</buildCommand>
|
|
||||||
<buildArguments>-j5</buildArguments>
|
|
||||||
<buildTarget>testPose2SLAM.run</buildTarget>
|
|
||||||
<stopOnError>true</stopOnError>
|
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
|
||||||
<runAllBuilders>true</runAllBuilders>
|
|
||||||
</target>
|
|
||||||
<target name="testPose3SLAM.run" path="build/gtsam/slam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
|
||||||
<buildCommand>make</buildCommand>
|
|
||||||
<buildArguments>-j5</buildArguments>
|
|
||||||
<buildTarget>testPose3SLAM.run</buildTarget>
|
|
||||||
<stopOnError>true</stopOnError>
|
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
|
||||||
<runAllBuilders>true</runAllBuilders>
|
|
||||||
</target>
|
|
||||||
<target name="testSimulated2D.run" path="build/gtsam/slam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
|
||||||
<buildCommand>make</buildCommand>
|
|
||||||
<buildArguments>-j5</buildArguments>
|
|
||||||
<buildTarget>testSimulated2D.run</buildTarget>
|
|
||||||
<stopOnError>true</stopOnError>
|
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
|
||||||
<runAllBuilders>true</runAllBuilders>
|
|
||||||
</target>
|
|
||||||
<target name="testSimulated2DOriented.run" path="build/gtsam/slam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
|
||||||
<buildCommand>make</buildCommand>
|
|
||||||
<buildArguments>-j5</buildArguments>
|
|
||||||
<buildTarget>testSimulated2DOriented.run</buildTarget>
|
|
||||||
<stopOnError>true</stopOnError>
|
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
|
||||||
<runAllBuilders>true</runAllBuilders>
|
|
||||||
</target>
|
|
||||||
<target name="testVisualSLAM.run" path="build/gtsam/slam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
|
||||||
<buildCommand>make</buildCommand>
|
|
||||||
<buildArguments>-j5</buildArguments>
|
|
||||||
<buildTarget>testVisualSLAM.run</buildTarget>
|
|
||||||
<stopOnError>true</stopOnError>
|
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
|
||||||
<runAllBuilders>true</runAllBuilders>
|
|
||||||
</target>
|
|
||||||
<target name="testProjectionFactor.run" path="build/gtsam/slam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testProjectionFactor.run" path="build/gtsam/slam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
<buildArguments>-j5</buildArguments>
|
<buildArguments>-j5</buildArguments>
|
||||||
|
@ -675,14 +627,6 @@
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
<runAllBuilders>true</runAllBuilders>
|
<runAllBuilders>true</runAllBuilders>
|
||||||
</target>
|
</target>
|
||||||
<target name="testSerializationSLAM.run" path="build/gtsam/slam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
|
||||||
<buildCommand>make</buildCommand>
|
|
||||||
<buildArguments>-j5</buildArguments>
|
|
||||||
<buildTarget>testSerializationSLAM.run</buildTarget>
|
|
||||||
<stopOnError>true</stopOnError>
|
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
|
||||||
<runAllBuilders>true</runAllBuilders>
|
|
||||||
</target>
|
|
||||||
<target name="testGeneralSFMFactor_Cal3Bundler.run" path="build/gtsam/slam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testGeneralSFMFactor_Cal3Bundler.run" path="build/gtsam/slam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
<buildArguments>-j5</buildArguments>
|
<buildArguments>-j5</buildArguments>
|
||||||
|
@ -691,6 +635,14 @@
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
<runAllBuilders>true</runAllBuilders>
|
<runAllBuilders>true</runAllBuilders>
|
||||||
</target>
|
</target>
|
||||||
|
<target name="testSerialization.run" path="build/gtsam/slam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
|
<buildCommand>make</buildCommand>
|
||||||
|
<buildArguments>-j5</buildArguments>
|
||||||
|
<buildTarget>testSerialization.run</buildTarget>
|
||||||
|
<stopOnError>true</stopOnError>
|
||||||
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
<runAllBuilders>true</runAllBuilders>
|
||||||
|
</target>
|
||||||
<target name="testValues.run" path="build/gtsam/nonlinear" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testValues.run" path="build/gtsam/nonlinear" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
<buildArguments>-j5</buildArguments>
|
<buildArguments>-j5</buildArguments>
|
||||||
|
@ -1163,6 +1115,14 @@
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
<runAllBuilders>true</runAllBuilders>
|
<runAllBuilders>true</runAllBuilders>
|
||||||
</target>
|
</target>
|
||||||
|
<target name="testSerializationSLAM.run" path="build/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
|
<buildCommand>make</buildCommand>
|
||||||
|
<buildArguments>-j5</buildArguments>
|
||||||
|
<buildTarget>testSerializationSLAM.run</buildTarget>
|
||||||
|
<stopOnError>true</stopOnError>
|
||||||
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
<runAllBuilders>true</runAllBuilders>
|
||||||
|
</target>
|
||||||
<target name="clean" path="build/wrap/gtsam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="clean" path="build/wrap/gtsam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
<buildArguments>-j5</buildArguments>
|
<buildArguments>-j5</buildArguments>
|
||||||
|
|
|
@ -0,0 +1,92 @@
|
||||||
|
/* ----------------------------------------------------------------------------
|
||||||
|
|
||||||
|
* 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
|
||||||
|
|
||||||
|
* -------------------------------------------------------------------------- */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @file serialization.h
|
||||||
|
* @brief Convenience functions for serializing data structures via boost.serialization
|
||||||
|
* @author Alex Cunningham
|
||||||
|
* @author Richard Roberts
|
||||||
|
* @date Feb 7, 2012
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <sstream>
|
||||||
|
#include <string>
|
||||||
|
|
||||||
|
// includes for standard serialization types
|
||||||
|
#include <boost/serialization/export.hpp>
|
||||||
|
#include <boost/serialization/optional.hpp>
|
||||||
|
#include <boost/serialization/shared_ptr.hpp>
|
||||||
|
#include <boost/serialization/vector.hpp>
|
||||||
|
#include <boost/serialization/map.hpp>
|
||||||
|
#include <boost/serialization/list.hpp>
|
||||||
|
#include <boost/serialization/deque.hpp>
|
||||||
|
#include <boost/serialization/weak_ptr.hpp>
|
||||||
|
|
||||||
|
#include <boost/archive/text_oarchive.hpp>
|
||||||
|
#include <boost/archive/text_iarchive.hpp>
|
||||||
|
#include <boost/archive/xml_iarchive.hpp>
|
||||||
|
#include <boost/archive/xml_oarchive.hpp>
|
||||||
|
#include <boost/archive/binary_iarchive.hpp>
|
||||||
|
#include <boost/archive/binary_oarchive.hpp>
|
||||||
|
|
||||||
|
namespace gtsam {
|
||||||
|
|
||||||
|
// Serialization directly to strings in compressed format
|
||||||
|
template<class T>
|
||||||
|
std::string serialize(const T& input) {
|
||||||
|
std::ostringstream out_archive_stream;
|
||||||
|
boost::archive::text_oarchive out_archive(out_archive_stream);
|
||||||
|
out_archive << input;
|
||||||
|
return out_archive_stream.str();
|
||||||
|
}
|
||||||
|
|
||||||
|
template<class T>
|
||||||
|
void deserialize(const std::string& serialized, T& output) {
|
||||||
|
std::istringstream in_archive_stream(serialized);
|
||||||
|
boost::archive::text_iarchive in_archive(in_archive_stream);
|
||||||
|
in_archive >> output;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Serialization to XML format with named structures
|
||||||
|
template<class T>
|
||||||
|
std::string serializeXML(const T& input, const std::string& name="data") {
|
||||||
|
std::ostringstream out_archive_stream;
|
||||||
|
boost::archive::xml_oarchive out_archive(out_archive_stream);
|
||||||
|
out_archive << boost::serialization::make_nvp(name.c_str(), input);
|
||||||
|
return out_archive_stream.str();
|
||||||
|
}
|
||||||
|
|
||||||
|
template<class T>
|
||||||
|
void deserializeXML(const std::string& serialized, T& output, const std::string& name="data") {
|
||||||
|
std::istringstream in_archive_stream(serialized);
|
||||||
|
boost::archive::xml_iarchive in_archive(in_archive_stream);
|
||||||
|
in_archive >> boost::serialization::make_nvp(name.c_str(), output);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Serialization to binary format with named structures
|
||||||
|
template<class T>
|
||||||
|
std::string serializeBinary(const T& input, const std::string& name="data") {
|
||||||
|
std::ostringstream out_archive_stream;
|
||||||
|
boost::archive::binary_oarchive out_archive(out_archive_stream);
|
||||||
|
out_archive << boost::serialization::make_nvp(name.c_str(), input);
|
||||||
|
return out_archive_stream.str();
|
||||||
|
}
|
||||||
|
|
||||||
|
template<class T>
|
||||||
|
void deserializeBinary(const std::string& serialized, T& output, const std::string& name="data") {
|
||||||
|
std::istringstream in_archive_stream(serialized);
|
||||||
|
boost::archive::binary_iarchive in_archive(in_archive_stream);
|
||||||
|
in_archive >> boost::serialization::make_nvp(name.c_str(), output);
|
||||||
|
}
|
||||||
|
|
||||||
|
} // \namespace gtsam
|
|
@ -22,46 +22,14 @@
|
||||||
#include <sstream>
|
#include <sstream>
|
||||||
#include <string>
|
#include <string>
|
||||||
|
|
||||||
// includes for standard serialization types
|
#include <gtsam/base/serialization.h>
|
||||||
#include <boost/serialization/export.hpp>
|
|
||||||
#include <boost/serialization/optional.hpp>
|
|
||||||
#include <boost/serialization/shared_ptr.hpp>
|
|
||||||
#include <boost/serialization/vector.hpp>
|
|
||||||
#include <boost/serialization/map.hpp>
|
|
||||||
#include <boost/serialization/list.hpp>
|
|
||||||
#include <boost/serialization/deque.hpp>
|
|
||||||
#include <boost/serialization/weak_ptr.hpp>
|
|
||||||
|
|
||||||
#include <boost/archive/text_oarchive.hpp>
|
|
||||||
#include <boost/archive/text_iarchive.hpp>
|
|
||||||
#include <boost/archive/xml_iarchive.hpp>
|
|
||||||
#include <boost/archive/xml_oarchive.hpp>
|
|
||||||
#include <boost/archive/binary_iarchive.hpp>
|
|
||||||
#include <boost/archive/binary_oarchive.hpp>
|
|
||||||
|
|
||||||
// whether to print the serialized text to stdout
|
// whether to print the serialized text to stdout
|
||||||
const bool verbose = false;
|
const bool verbose = false;
|
||||||
|
|
||||||
namespace gtsam { namespace serializationTestHelpers {
|
namespace gtsam {
|
||||||
|
namespace serializationTestHelpers {
|
||||||
|
|
||||||
/* ************************************************************************* */
|
|
||||||
// Serialization testing code.
|
|
||||||
/* ************************************************************************* */
|
|
||||||
|
|
||||||
template<class T>
|
|
||||||
std::string serialize(const T& input) {
|
|
||||||
std::ostringstream out_archive_stream;
|
|
||||||
boost::archive::text_oarchive out_archive(out_archive_stream);
|
|
||||||
out_archive << input;
|
|
||||||
return out_archive_stream.str();
|
|
||||||
}
|
|
||||||
|
|
||||||
template<class T>
|
|
||||||
void deserialize(const std::string& serialized, T& output) {
|
|
||||||
std::istringstream in_archive_stream(serialized);
|
|
||||||
boost::archive::text_iarchive in_archive(in_archive_stream);
|
|
||||||
in_archive >> output;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Templated round-trip serialization
|
// Templated round-trip serialization
|
||||||
template<class T>
|
template<class T>
|
||||||
|
@ -97,22 +65,6 @@ bool equalsDereferenced(const T& input) {
|
||||||
return input->equals(*output);
|
return input->equals(*output);
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
|
||||||
template<class T>
|
|
||||||
std::string serializeXML(const T& input) {
|
|
||||||
std::ostringstream out_archive_stream;
|
|
||||||
boost::archive::xml_oarchive out_archive(out_archive_stream);
|
|
||||||
out_archive << boost::serialization::make_nvp("data", input);
|
|
||||||
return out_archive_stream.str();
|
|
||||||
}
|
|
||||||
|
|
||||||
template<class T>
|
|
||||||
void deserializeXML(const std::string& serialized, T& output) {
|
|
||||||
std::istringstream in_archive_stream(serialized);
|
|
||||||
boost::archive::xml_iarchive in_archive(in_archive_stream);
|
|
||||||
in_archive >> boost::serialization::make_nvp("data", output);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Templated round-trip serialization using XML
|
// Templated round-trip serialization using XML
|
||||||
template<class T>
|
template<class T>
|
||||||
void roundtripXML(const T& input, T& output) {
|
void roundtripXML(const T& input, T& output) {
|
||||||
|
@ -148,22 +100,6 @@ bool equalsDereferencedXML(const T& input = T()) {
|
||||||
return input->equals(*output);
|
return input->equals(*output);
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
|
||||||
template<class T>
|
|
||||||
std::string serializeBinary(const T& input) {
|
|
||||||
std::ostringstream out_archive_stream;
|
|
||||||
boost::archive::binary_oarchive out_archive(out_archive_stream);
|
|
||||||
out_archive << boost::serialization::make_nvp("data", input);
|
|
||||||
return out_archive_stream.str();
|
|
||||||
}
|
|
||||||
|
|
||||||
template<class T>
|
|
||||||
void deserializeBinary(const std::string& serialized, T& output) {
|
|
||||||
std::istringstream in_archive_stream(serialized);
|
|
||||||
boost::archive::binary_iarchive in_archive(in_archive_stream);
|
|
||||||
in_archive >> boost::serialization::make_nvp("data", output);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Templated round-trip serialization using XML
|
// Templated round-trip serialization using XML
|
||||||
template<class T>
|
template<class T>
|
||||||
void roundtripBinary(const T& input, T& output) {
|
void roundtripBinary(const T& input, T& output) {
|
||||||
|
@ -199,4 +135,6 @@ bool equalsDereferencedBinary(const T& input = T()) {
|
||||||
return input->equals(*output);
|
return input->equals(*output);
|
||||||
}
|
}
|
||||||
|
|
||||||
} }
|
} // \namespace serializationTestHelpers
|
||||||
|
} // \namespace gtsam
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,257 @@
|
||||||
|
/**
|
||||||
|
* @file serialization.cpp
|
||||||
|
*
|
||||||
|
* @date Jun 12, 2013
|
||||||
|
* @author Alex Cunningham
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <gtsam/slam/serialization.h>
|
||||||
|
#include <gtsam/base/serialization.h>
|
||||||
|
|
||||||
|
//#include <gtsam/slam/AntiFactor.h>
|
||||||
|
#include <gtsam/slam/BearingFactor.h>
|
||||||
|
#include <gtsam/slam/BearingRangeFactor.h>
|
||||||
|
#include <gtsam/slam/BetweenFactor.h>
|
||||||
|
//#include <gtsam/slam/BoundingConstraint.h>
|
||||||
|
#include <gtsam/slam/GeneralSFMFactor.h>
|
||||||
|
#include <gtsam/slam/PriorFactor.h>
|
||||||
|
#include <gtsam/slam/ProjectionFactor.h>
|
||||||
|
#include <gtsam/slam/RangeFactor.h>
|
||||||
|
#include <gtsam/slam/StereoFactor.h>
|
||||||
|
#include <gtsam/nonlinear/NonlinearEquality.h>
|
||||||
|
#include <gtsam/nonlinear/Symbol.h>
|
||||||
|
#include <gtsam/linear/GaussianISAM.h>
|
||||||
|
#include <gtsam/linear/GaussianMultifrontalSolver.h>
|
||||||
|
#include <gtsam/base/LieVector.h>
|
||||||
|
#include <gtsam/base/LieMatrix.h>
|
||||||
|
//#include <gtsam/geometry/StereoPoint2.h>
|
||||||
|
#include <gtsam/geometry/Pose2.h>
|
||||||
|
#include <gtsam/geometry/Pose3.h>
|
||||||
|
#include <gtsam/geometry/Cal3DS2.h>
|
||||||
|
//#include <gtsam/geometry/Cal3_S2Stereo.h>
|
||||||
|
|
||||||
|
using namespace gtsam;
|
||||||
|
|
||||||
|
// Creating as many permutations of factors as possible
|
||||||
|
typedef PriorFactor<LieVector> PriorFactorLieVector;
|
||||||
|
typedef PriorFactor<LieMatrix> PriorFactorLieMatrix;
|
||||||
|
typedef PriorFactor<Point2> PriorFactorPoint2;
|
||||||
|
typedef PriorFactor<StereoPoint2> PriorFactorStereoPoint2;
|
||||||
|
typedef PriorFactor<Point3> PriorFactorPoint3;
|
||||||
|
typedef PriorFactor<Rot2> PriorFactorRot2;
|
||||||
|
typedef PriorFactor<Rot3> PriorFactorRot3;
|
||||||
|
typedef PriorFactor<Pose2> PriorFactorPose2;
|
||||||
|
typedef PriorFactor<Pose3> PriorFactorPose3;
|
||||||
|
typedef PriorFactor<Cal3_S2> PriorFactorCal3_S2;
|
||||||
|
typedef PriorFactor<Cal3DS2> PriorFactorCal3DS2;
|
||||||
|
typedef PriorFactor<CalibratedCamera> PriorFactorCalibratedCamera;
|
||||||
|
typedef PriorFactor<SimpleCamera> PriorFactorSimpleCamera;
|
||||||
|
typedef PriorFactor<StereoCamera> PriorFactorStereoCamera;
|
||||||
|
|
||||||
|
typedef BetweenFactor<LieVector> BetweenFactorLieVector;
|
||||||
|
typedef BetweenFactor<LieMatrix> BetweenFactorLieMatrix;
|
||||||
|
typedef BetweenFactor<Point2> BetweenFactorPoint2;
|
||||||
|
typedef BetweenFactor<Point3> BetweenFactorPoint3;
|
||||||
|
typedef BetweenFactor<Rot2> BetweenFactorRot2;
|
||||||
|
typedef BetweenFactor<Rot3> BetweenFactorRot3;
|
||||||
|
typedef BetweenFactor<Pose2> BetweenFactorPose2;
|
||||||
|
typedef BetweenFactor<Pose3> BetweenFactorPose3;
|
||||||
|
|
||||||
|
typedef NonlinearEquality<LieVector> NonlinearEqualityLieVector;
|
||||||
|
typedef NonlinearEquality<LieMatrix> NonlinearEqualityLieMatrix;
|
||||||
|
typedef NonlinearEquality<Point2> NonlinearEqualityPoint2;
|
||||||
|
typedef NonlinearEquality<StereoPoint2> NonlinearEqualityStereoPoint2;
|
||||||
|
typedef NonlinearEquality<Point3> NonlinearEqualityPoint3;
|
||||||
|
typedef NonlinearEquality<Rot2> NonlinearEqualityRot2;
|
||||||
|
typedef NonlinearEquality<Rot3> NonlinearEqualityRot3;
|
||||||
|
typedef NonlinearEquality<Pose2> NonlinearEqualityPose2;
|
||||||
|
typedef NonlinearEquality<Pose3> NonlinearEqualityPose3;
|
||||||
|
typedef NonlinearEquality<Cal3_S2> NonlinearEqualityCal3_S2;
|
||||||
|
typedef NonlinearEquality<Cal3DS2> NonlinearEqualityCal3DS2;
|
||||||
|
typedef NonlinearEquality<CalibratedCamera> NonlinearEqualityCalibratedCamera;
|
||||||
|
typedef NonlinearEquality<SimpleCamera> NonlinearEqualitySimpleCamera;
|
||||||
|
typedef NonlinearEquality<StereoCamera> NonlinearEqualityStereoCamera;
|
||||||
|
|
||||||
|
typedef RangeFactor<Pose2, Point2> RangeFactorPosePoint2;
|
||||||
|
typedef RangeFactor<Pose3, Point3> RangeFactorPosePoint3;
|
||||||
|
typedef RangeFactor<Pose2, Pose2> RangeFactorPose2;
|
||||||
|
typedef RangeFactor<Pose3, Pose3> RangeFactorPose3;
|
||||||
|
typedef RangeFactor<CalibratedCamera, Point3> RangeFactorCalibratedCameraPoint;
|
||||||
|
typedef RangeFactor<SimpleCamera, Point3> RangeFactorSimpleCameraPoint;
|
||||||
|
typedef RangeFactor<CalibratedCamera, CalibratedCamera> RangeFactorCalibratedCamera;
|
||||||
|
typedef RangeFactor<SimpleCamera, SimpleCamera> RangeFactorSimpleCamera;
|
||||||
|
|
||||||
|
typedef BearingFactor<Pose2, Point2, Rot2> BearingFactor2D;
|
||||||
|
typedef BearingFactor<Pose3, Point3, Rot3> BearingFactor3D;
|
||||||
|
|
||||||
|
typedef BearingRangeFactor<Pose2, Point2> BearingRangeFactor2D;
|
||||||
|
typedef BearingRangeFactor<Pose3, Point3> BearingRangeFactor3D;
|
||||||
|
|
||||||
|
typedef GenericProjectionFactor<Pose3, Point3, Cal3_S2> GenericProjectionFactorCal3_S2;
|
||||||
|
typedef GenericProjectionFactor<Pose3, Point3, Cal3DS2> GenericProjectionFactorCal3DS2;
|
||||||
|
|
||||||
|
typedef gtsam::GeneralSFMFactor<gtsam::SimpleCamera, gtsam::Point3> GeneralSFMFactorCal3_S2;
|
||||||
|
//typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3DS2, gtsam::Point3> GeneralSFMFactorCal3DS2;
|
||||||
|
|
||||||
|
typedef gtsam::GeneralSFMFactor2<gtsam::Cal3_S2> GeneralSFMFactor2Cal3_S2;
|
||||||
|
|
||||||
|
typedef gtsam::GenericStereoFactor<gtsam::Pose3, gtsam::Point3> GenericStereoFactor3D;
|
||||||
|
|
||||||
|
|
||||||
|
/* Create GUIDs for 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");
|
||||||
|
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Base , "gtsam_noiseModel_mEstimator_Base");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Null , "gtsam_noiseModel_mEstimator_Null");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Fair , "gtsam_noiseModel_mEstimator_Fair");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Huber, "gtsam_noiseModel_mEstimator_Huber");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Tukey, "gtsam_noiseModel_mEstimator_Tukey");
|
||||||
|
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal");
|
||||||
|
|
||||||
|
/* Create GUIDs for geometry */
|
||||||
|
/* ************************************************************************* */
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::LieVector);
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::LieMatrix);
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::Point2);
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::StereoPoint2);
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::Point3);
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::Rot2);
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::Rot3);
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::Pose2);
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::Pose3);
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::Cal3_S2);
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::Cal3DS2);
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::Cal3_S2Stereo);
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::CalibratedCamera);
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::SimpleCamera);
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::StereoCamera);
|
||||||
|
|
||||||
|
/* Create GUIDs for factors */
|
||||||
|
/* ************************************************************************* */
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::JacobianFactor, "gtsam::JacobianFactor");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::HessianFactor , "gtsam::HessianFactor");
|
||||||
|
|
||||||
|
BOOST_CLASS_EXPORT_GUID(PriorFactorLieVector, "gtsam::PriorFactorLieVector");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(PriorFactorLieMatrix, "gtsam::PriorFactorLieMatrix");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(PriorFactorPoint2, "gtsam::PriorFactorPoint2");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(PriorFactorStereoPoint2, "gtsam::PriorFactorStereoPoint2");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(PriorFactorPoint3, "gtsam::PriorFactorPoint3");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(PriorFactorRot2, "gtsam::PriorFactorRot2");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(PriorFactorRot3, "gtsam::PriorFactorRot3");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(PriorFactorPose2, "gtsam::PriorFactorPose2");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(PriorFactorPose3, "gtsam::PriorFactorPose3");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(PriorFactorCal3_S2, "gtsam::PriorFactorCal3_S2");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(PriorFactorCal3DS2, "gtsam::PriorFactorCal3DS2");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(PriorFactorCalibratedCamera, "gtsam::PriorFactorCalibratedCamera");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(PriorFactorSimpleCamera, "gtsam::PriorFactorSimpleCamera");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(PriorFactorStereoCamera, "gtsam::PriorFactorStereoCamera");
|
||||||
|
|
||||||
|
BOOST_CLASS_EXPORT_GUID(BetweenFactorLieVector, "gtsam::BetweenFactorLieVector");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(BetweenFactorLieMatrix, "gtsam::BetweenFactorLieMatrix");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(BetweenFactorPoint2, "gtsam::BetweenFactorPoint2");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(BetweenFactorPoint3, "gtsam::BetweenFactorPoint3");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(BetweenFactorRot2, "gtsam::BetweenFactorRot2");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(BetweenFactorRot3, "gtsam::BetweenFactorRot3");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(BetweenFactorPose2, "gtsam::BetweenFactorPose2");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(BetweenFactorPose3, "gtsam::BetweenFactorPose3");
|
||||||
|
|
||||||
|
BOOST_CLASS_EXPORT_GUID(NonlinearEqualityLieVector, "gtsam::NonlinearEqualityLieVector");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(NonlinearEqualityLieMatrix, "gtsam::NonlinearEqualityLieMatrix");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(NonlinearEqualityPoint2, "gtsam::NonlinearEqualityPoint2");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(NonlinearEqualityStereoPoint2, "gtsam::NonlinearEqualityStereoPoint2");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(NonlinearEqualityPoint3, "gtsam::NonlinearEqualityPoint3");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(NonlinearEqualityRot2, "gtsam::NonlinearEqualityRot2");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(NonlinearEqualityRot3, "gtsam::NonlinearEqualityRot3");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(NonlinearEqualityPose2, "gtsam::NonlinearEqualityPose2");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(NonlinearEqualityPose3, "gtsam::NonlinearEqualityPose3");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(NonlinearEqualityCal3_S2, "gtsam::NonlinearEqualityCal3_S2");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(NonlinearEqualityCal3DS2, "gtsam::NonlinearEqualityCal3DS2");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(NonlinearEqualityCalibratedCamera, "gtsam::NonlinearEqualityCalibratedCamera");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(NonlinearEqualitySimpleCamera, "gtsam::NonlinearEqualitySimpleCamera");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(NonlinearEqualityStereoCamera, "gtsam::NonlinearEqualityStereoCamera");
|
||||||
|
|
||||||
|
BOOST_CLASS_EXPORT_GUID(RangeFactorPosePoint2, "gtsam::RangeFactorPosePoint2");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(RangeFactorPosePoint3, "gtsam::RangeFactorPosePoint3");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(RangeFactorPose2, "gtsam::RangeFactorPose2");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(RangeFactorPose3, "gtsam::RangeFactorPose3");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(RangeFactorCalibratedCameraPoint, "gtsam::RangeFactorCalibratedCameraPoint");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(RangeFactorSimpleCameraPoint, "gtsam::RangeFactorSimpleCameraPoint");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(RangeFactorCalibratedCamera, "gtsam::RangeFactorCalibratedCamera");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(RangeFactorSimpleCamera, "gtsam::RangeFactorSimpleCamera");
|
||||||
|
|
||||||
|
BOOST_CLASS_EXPORT_GUID(BearingFactor2D, "gtsam::BearingFactor2D");
|
||||||
|
|
||||||
|
BOOST_CLASS_EXPORT_GUID(BearingRangeFactor2D, "gtsam::BearingRangeFactor2D");
|
||||||
|
|
||||||
|
BOOST_CLASS_EXPORT_GUID(GenericProjectionFactorCal3_S2, "gtsam::GenericProjectionFactorCal3_S2");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(GenericProjectionFactorCal3DS2, "gtsam::GenericProjectionFactorCal3DS2");
|
||||||
|
|
||||||
|
BOOST_CLASS_EXPORT_GUID(GeneralSFMFactorCal3_S2, "gtsam::GeneralSFMFactorCal3_S2");
|
||||||
|
//BOOST_CLASS_EXPORT_GUID(GeneralSFMFactorCal3DS2, "gtsam::GeneralSFMFactorCal3DS2");
|
||||||
|
|
||||||
|
BOOST_CLASS_EXPORT_GUID(GeneralSFMFactor2Cal3_S2, "gtsam::GeneralSFMFactor2Cal3_S2");
|
||||||
|
|
||||||
|
BOOST_CLASS_EXPORT_GUID(GenericStereoFactor3D, "gtsam::GenericStereoFactor3D");
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
// Actual implementations of functions
|
||||||
|
/* ************************************************************************* */
|
||||||
|
std::string gtsam::serializeGraph(const NonlinearFactorGraph& graph) {
|
||||||
|
return serialize<NonlinearFactorGraph>(graph);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
NonlinearFactorGraph gtsam::deserializeGraph(const std::string& serialized_graph) {
|
||||||
|
NonlinearFactorGraph result;
|
||||||
|
deserialize<NonlinearFactorGraph>(serialized_graph, result);
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
std::string gtsam::serializeGraphXML(const NonlinearFactorGraph& graph, const std::string& name) {
|
||||||
|
return serializeXML<NonlinearFactorGraph>(graph, name);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
NonlinearFactorGraph gtsam::deserializeGraphXML(const std::string& serialized_graph,
|
||||||
|
const std::string& name) {
|
||||||
|
NonlinearFactorGraph result;
|
||||||
|
deserializeXML<NonlinearFactorGraph>(serialized_graph, result, name);
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
std::string gtsam::serializeValues(const Values& values) {
|
||||||
|
return serialize<Values>(values);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
Values gtsam::deserializeValues(const std::string& serialized_values) {
|
||||||
|
Values result;
|
||||||
|
deserialize<Values>(serialized_values, result);
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
std::string gtsam::serializeValuesXML(const Values& values, const std::string& name) {
|
||||||
|
return serializeXML<Values>(values, name);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
Values gtsam::deserializeValuesXML(const std::string& serialized_values,
|
||||||
|
const std::string& name) {
|
||||||
|
Values result;
|
||||||
|
deserializeXML<Values>(serialized_values, result, name);
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,40 @@
|
||||||
|
/**
|
||||||
|
* @file serialization.h
|
||||||
|
*
|
||||||
|
* @brief Global functions for performing serialization, designed for use with matlab
|
||||||
|
*
|
||||||
|
* @date Jun 12, 2013
|
||||||
|
* @author Alex Cunningham
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
||||||
|
|
||||||
|
namespace gtsam {
|
||||||
|
|
||||||
|
// Serialize/Deserialize a NonlinearFactorGraph
|
||||||
|
std::string serializeGraph(const NonlinearFactorGraph& graph);
|
||||||
|
|
||||||
|
NonlinearFactorGraph deserializeGraph(const std::string& serialized_graph);
|
||||||
|
|
||||||
|
std::string serializeGraphXML(const NonlinearFactorGraph& graph,
|
||||||
|
const std::string& name = "graph");
|
||||||
|
|
||||||
|
NonlinearFactorGraph deserializeGraphXML(const std::string& serialized_graph,
|
||||||
|
const std::string& name = "graph");
|
||||||
|
|
||||||
|
|
||||||
|
// Serialize/Deserialize a Values
|
||||||
|
std::string serializeValues(const Values& values);
|
||||||
|
|
||||||
|
Values deserializeValues(const std::string& serialized_values);
|
||||||
|
|
||||||
|
std::string serializeValuesXML(const Values& values, const std::string& name = "values");
|
||||||
|
|
||||||
|
Values deserializeValuesXML(const std::string& serialized_values,
|
||||||
|
const std::string& name = "values");
|
||||||
|
|
||||||
|
} // \namespace gtsam
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,75 @@
|
||||||
|
/**
|
||||||
|
* @file testSerialization.cpp
|
||||||
|
*
|
||||||
|
* @brief Tests for serialization global functions using boost.serialization
|
||||||
|
*
|
||||||
|
* @date Jun 12, 2013
|
||||||
|
* @author Alex Cunningham
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <CppUnitLite/TestHarness.h>
|
||||||
|
|
||||||
|
#include <gtsam/slam/serialization.h>
|
||||||
|
|
||||||
|
#include <gtsam/geometry/Pose2.h>
|
||||||
|
#include <gtsam/geometry/Pose3.h>
|
||||||
|
|
||||||
|
#include <gtsam/slam/PriorFactor.h>
|
||||||
|
#include <gtsam/slam/BetweenFactor.h>
|
||||||
|
|
||||||
|
using namespace std;
|
||||||
|
using namespace gtsam;
|
||||||
|
|
||||||
|
Values exampleValues() {
|
||||||
|
Values result;
|
||||||
|
result.insert(234, gtsam::Rot2::fromAngle(0.1));
|
||||||
|
result.insert(123, gtsam::Point2(1.0, 2.0));
|
||||||
|
result.insert(254, gtsam::Pose2(1.0, 2.0, 0.3));
|
||||||
|
result.insert(678, gtsam::Rot3::Rx(0.1));
|
||||||
|
result.insert(498, gtsam::Point3(1.0, 2.0, 3.0));
|
||||||
|
result.insert(345, gtsam::Pose3(Rot3::Rx(0.1), Point3(1.0, 2.0, 3.0)));
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
NonlinearFactorGraph exampleGraph() {
|
||||||
|
NonlinearFactorGraph graph;
|
||||||
|
graph.add(PriorFactor<Pose2>(234, Pose2(1.0, 2.0, 0.3), noiseModel::Diagonal::Sigmas(ones(3))));
|
||||||
|
graph.add(BetweenFactor<Pose2>(234, 567, Pose2(1.0, 2.0, 0.3), noiseModel::Diagonal::Sigmas(ones(3))));
|
||||||
|
return graph;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
TEST( testSerialization, text_graph_serialization ) {
|
||||||
|
NonlinearFactorGraph graph = exampleGraph();
|
||||||
|
string serialized = serializeGraph(graph);
|
||||||
|
NonlinearFactorGraph actGraph = deserializeGraph(serialized);
|
||||||
|
EXPECT(assert_equal(graph, actGraph));
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
TEST( testSerialization, xml_graph_serialization ) {
|
||||||
|
NonlinearFactorGraph graph = exampleGraph();
|
||||||
|
string serialized = serializeGraphXML(graph, "graph1");
|
||||||
|
NonlinearFactorGraph actGraph = deserializeGraphXML(serialized, "graph1");
|
||||||
|
EXPECT(assert_equal(graph, actGraph));
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
TEST( testSerialization, text_values_serialization ) {
|
||||||
|
Values values = exampleValues();
|
||||||
|
string serialized = serializeValues(values);
|
||||||
|
Values actValues = deserializeValues(serialized);
|
||||||
|
EXPECT(assert_equal(values, actValues));
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
TEST( testSerialization, xml_values_serialization ) {
|
||||||
|
Values values = exampleValues();
|
||||||
|
string serialized = serializeValuesXML(values, "values1");
|
||||||
|
Values actValues = deserializeValuesXML(serialized, "values1");
|
||||||
|
EXPECT(assert_equal(values, actValues, 1e-5));
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
|
||||||
|
/* ************************************************************************* */
|
|
@ -133,6 +133,13 @@ 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::Gaussian, "gtsam_noiseModel_Gaussian");
|
||||||
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Unit, "gtsam_noiseModel_Unit");
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Unit, "gtsam_noiseModel_Unit");
|
||||||
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, "gtsam_noiseModel_Isotropic");
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, "gtsam_noiseModel_Isotropic");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Robust, "gtsam_noiseModel_Robust");
|
||||||
|
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Base , "gtsam_noiseModel_mEstimator_Base");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Null , "gtsam_noiseModel_mEstimator_Null");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Fair , "gtsam_noiseModel_mEstimator_Fair");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Huber, "gtsam_noiseModel_mEstimator_Huber");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Tukey, "gtsam_noiseModel_mEstimator_Tukey");
|
||||||
|
|
||||||
BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel");
|
BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel");
|
||||||
BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal");
|
BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal");
|
||||||
|
@ -155,7 +162,6 @@ BOOST_CLASS_EXPORT(gtsam::CalibratedCamera);
|
||||||
BOOST_CLASS_EXPORT(gtsam::SimpleCamera);
|
BOOST_CLASS_EXPORT(gtsam::SimpleCamera);
|
||||||
BOOST_CLASS_EXPORT(gtsam::StereoCamera);
|
BOOST_CLASS_EXPORT(gtsam::StereoCamera);
|
||||||
|
|
||||||
|
|
||||||
/* Create GUIDs for factors */
|
/* Create GUIDs for factors */
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
BOOST_CLASS_EXPORT_GUID(gtsam::JacobianFactor, "gtsam::JacobianFactor");
|
BOOST_CLASS_EXPORT_GUID(gtsam::JacobianFactor, "gtsam::JacobianFactor");
|
||||||
|
@ -225,7 +231,7 @@ BOOST_CLASS_EXPORT_GUID(GenericStereoFactor3D, "gtsam::GenericStereoFactor3D");
|
||||||
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
TEST (Serialization, smallExample_linear) {
|
TEST (testSerializationSLAM, smallExample_linear) {
|
||||||
using namespace example;
|
using namespace example;
|
||||||
|
|
||||||
Ordering ordering; ordering += X(1),X(2),L(1);
|
Ordering ordering; ordering += X(1),X(2),L(1);
|
||||||
|
@ -245,7 +251,7 @@ TEST (Serialization, smallExample_linear) {
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
TEST (Serialization, gaussianISAM) {
|
TEST (testSerializationSLAM, gaussianISAM) {
|
||||||
using namespace example;
|
using namespace example;
|
||||||
Ordering ordering;
|
Ordering ordering;
|
||||||
GaussianFactorGraph smoother;
|
GaussianFactorGraph smoother;
|
||||||
|
@ -265,7 +271,7 @@ BOOST_CLASS_EXPORT_GUID(simulated2D::Odometry, "gtsam::simulated2D::Odometry"
|
||||||
BOOST_CLASS_EXPORT_GUID(simulated2D::Measurement, "gtsam::simulated2D::Measurement")
|
BOOST_CLASS_EXPORT_GUID(simulated2D::Measurement, "gtsam::simulated2D::Measurement")
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
TEST (Serialization, smallExample_nonlinear) {
|
TEST (testSerializationSLAM, smallExample_nonlinear) {
|
||||||
using namespace example;
|
using namespace example;
|
||||||
NonlinearFactorGraph nfg = createNonlinearFactorGraph();
|
NonlinearFactorGraph nfg = createNonlinearFactorGraph();
|
||||||
Values c1 = createValues();
|
Values c1 = createValues();
|
||||||
|
@ -279,7 +285,7 @@ TEST (Serialization, smallExample_nonlinear) {
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
TEST (Serialization, factors) {
|
TEST (testSerializationSLAM, factors) {
|
||||||
|
|
||||||
LieVector lieVector(4, 1.0, 2.0, 3.0, 4.0);
|
LieVector lieVector(4, 1.0, 2.0, 3.0, 4.0);
|
||||||
LieMatrix lieMatrix(2, 3, 1.0, 2.0, 3.0, 4.0, 5.0 ,6.0);
|
LieMatrix lieMatrix(2, 3, 1.0, 2.0, 3.0, 4.0, 5.0 ,6.0);
|
||||||
|
@ -331,7 +337,13 @@ TEST (Serialization, factors) {
|
||||||
SharedNoiseModel model9 = noiseModel::Isotropic::Sigma(9, 0.3);
|
SharedNoiseModel model9 = noiseModel::Isotropic::Sigma(9, 0.3);
|
||||||
SharedNoiseModel model11 = noiseModel::Isotropic::Sigma(11, 0.3);
|
SharedNoiseModel model11 = noiseModel::Isotropic::Sigma(11, 0.3);
|
||||||
|
|
||||||
|
SharedNoiseModel robust1 = noiseModel::Robust::Create(
|
||||||
|
noiseModel::mEstimator::Huber::Create(10.0, noiseModel::mEstimator::Huber::Scalar),
|
||||||
|
noiseModel::Unit::Create(2));
|
||||||
|
|
||||||
|
EXPECT(equalsDereferenced(robust1));
|
||||||
|
EXPECT(equalsDereferencedXML(robust1));
|
||||||
|
EXPECT(equalsDereferencedBinary(robust1));
|
||||||
|
|
||||||
PriorFactorLieVector priorFactorLieVector(a01, lieVector, model4);
|
PriorFactorLieVector priorFactorLieVector(a01, lieVector, model4);
|
||||||
PriorFactorLieMatrix priorFactorLieMatrix(a02, lieMatrix, model6);
|
PriorFactorLieMatrix priorFactorLieMatrix(a02, lieMatrix, model6);
|
||||||
|
@ -660,11 +672,8 @@ TEST (Serialization, factors) {
|
||||||
EXPECT(equalsBinary<GeneralSFMFactor2Cal3_S2>(generalSFMFactor2Cal3_S2));
|
EXPECT(equalsBinary<GeneralSFMFactor2Cal3_S2>(generalSFMFactor2Cal3_S2));
|
||||||
|
|
||||||
EXPECT(equalsBinary<GenericStereoFactor3D>(genericStereoFactor3D));
|
EXPECT(equalsBinary<GenericStereoFactor3D>(genericStereoFactor3D));
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
|
int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
|
Loading…
Reference in New Issue