correct PinholeCamera serialization problem. Add detailed comments for serialization in Value.h
parent
d584cf8500
commit
563e8fe77c
|
|
@ -143,15 +143,31 @@ namespace gtsam {
|
||||||
virtual ~Value() {}
|
virtual ~Value() {}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
/** Serialization function
|
/** Empty serialization function.
|
||||||
* All DERIVED classes derived from Value must put the following line in their serialization function:
|
*
|
||||||
* ar & boost::serialization::make_nvp("DERIVED", boost::serialization::base_object<Value>(*this));
|
* There are two important notes for successfully serializing derived objects in Values:
|
||||||
* Alternatively, if the derived class is template-based, for example PinholeCamera<Calibration>,
|
* (Those derived objects are stored as pointer to this abstract base class Value)
|
||||||
* it can put the following code in its serialization function
|
*
|
||||||
* ar & boost::serialization::void_cast_register<PinholeCamera<Calibration>, Value>(
|
* 1. All DERIVED classes derived from Value must put the following line in their serialization function:
|
||||||
* static_cast<PinholeCamera<Calibration> *>(NULL),
|
* ar & boost::serialization::make_nvp("DERIVED", boost::serialization::base_object<Value>(*this));
|
||||||
* static_cast<Value *>(NULL));
|
* or, alternatively
|
||||||
* See more: http://www.boost.org/doc/libs/1_45_0/libs/serialization/doc/serialization.html#runtimecasting
|
* ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Value);
|
||||||
|
* See: http://www.boost.org/doc/libs/release/libs/serialization/doc/serialization.html#runtimecasting
|
||||||
|
*
|
||||||
|
* 2. The source module that includes archive class headers to serialize objects of derived classes
|
||||||
|
* (boost/archive/text_oarchive.h, for example) must *export* all derived classes, using either
|
||||||
|
* BOOST_CLASS_EXPORT or BOOST_CLASS_EXPORT_GUID macros:
|
||||||
|
*
|
||||||
|
* BOOST_CLASS_EXPORT(DERIVED_CLASS_1)
|
||||||
|
* BOOST_CLASS_EXPORT_GUID(DERIVED_CLASS_2, "DERIVED_CLASS_2_ID_STRING")
|
||||||
|
*
|
||||||
|
* See: http://www.boost.org/doc/libs/release/libs/serialization/doc/serialization.html#derivedpointers
|
||||||
|
* http://www.boost.org/doc/libs/release/libs/serialization/doc/serialization.html#export
|
||||||
|
* http://www.boost.org/doc/libs/release/libs/serialization/doc/serialization.html#instantiation\
|
||||||
|
* http://www.boost.org/doc/libs/release/libs/serialization/doc/special.html#export
|
||||||
|
* http://www.boost.org/doc/libs/release/libs/serialization/doc/traits.html#export
|
||||||
|
* The last two links explain why this export line has to be in the same source module thaat includes
|
||||||
|
* any of the archive class headers.
|
||||||
* */
|
* */
|
||||||
friend class boost::serialization::access;
|
friend class boost::serialization::access;
|
||||||
template<class ARCHIVE>
|
template<class ARCHIVE>
|
||||||
|
|
|
||||||
|
|
@ -20,6 +20,7 @@
|
||||||
|
|
||||||
#include <cmath>
|
#include <cmath>
|
||||||
#include <boost/optional.hpp>
|
#include <boost/optional.hpp>
|
||||||
|
#include <boost/serialization/nvp.hpp>
|
||||||
#include <gtsam/base/DerivedValue.h>
|
#include <gtsam/base/DerivedValue.h>
|
||||||
#include <gtsam/base/Vector.h>
|
#include <gtsam/base/Vector.h>
|
||||||
#include <gtsam/base/Matrix.h>
|
#include <gtsam/base/Matrix.h>
|
||||||
|
|
@ -279,9 +280,7 @@ private:
|
||||||
friend class boost::serialization::access;
|
friend class boost::serialization::access;
|
||||||
template<class Archive>
|
template<class Archive>
|
||||||
void serialize(Archive & ar, const unsigned int version) {
|
void serialize(Archive & ar, const unsigned int version) {
|
||||||
ar & boost::serialization::void_cast_register<PinholeCamera<Calibration>, Value>(
|
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Value);
|
||||||
static_cast<PinholeCamera<Calibration> *>(NULL),
|
|
||||||
static_cast<Value *>(NULL));
|
|
||||||
ar & BOOST_SERIALIZATION_NVP(pose_);
|
ar & BOOST_SERIALIZATION_NVP(pose_);
|
||||||
ar & BOOST_SERIALIZATION_NVP(k_);
|
ar & BOOST_SERIALIZATION_NVP(k_);
|
||||||
}
|
}
|
||||||
|
|
|
||||||
|
|
@ -165,6 +165,7 @@ bool equalsDereferencedXML(const T& input = T()) {
|
||||||
using namespace std;
|
using namespace std;
|
||||||
using namespace gtsam;
|
using namespace gtsam;
|
||||||
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
TEST (Serialization, matrix_vector) {
|
TEST (Serialization, matrix_vector) {
|
||||||
EXPECT(equality<Vector>(Vector_(4, 1.0, 2.0, 3.0, 4.0)));
|
EXPECT(equality<Vector>(Vector_(4, 1.0, 2.0, 3.0, 4.0)));
|
||||||
|
|
@ -174,6 +175,24 @@ TEST (Serialization, matrix_vector) {
|
||||||
EXPECT(equalityXML<Matrix>(Matrix_(2, 2, 1.0, 2.0, 3.0, 4.0)));
|
EXPECT(equalityXML<Matrix>(Matrix_(2, 2, 1.0, 2.0, 3.0, 4.0)));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
// Export all classes derived from Value
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::Cal3_S2)
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::Cal3_S2Stereo)
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::Cal3Bundler)
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::CalibratedCamera)
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::Point2)
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::Point3)
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::Pose2)
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::Pose3)
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::Rot2)
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::Rot3)
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::PinholeCamera<Cal3_S2>)
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::PinholeCamera<Cal3DS2>)
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::PinholeCamera<Cal3Bundler>)
|
||||||
|
BOOST_CLASS_EXPORT(gtsam::StereoPoint2)
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
Point3 pt3(1.0, 2.0, 3.0);
|
Point3 pt3(1.0, 2.0, 3.0);
|
||||||
Rot3 rt3 = Rot3::RzRyRx(1.0, 3.0, 2.0);
|
Rot3 rt3 = Rot3::RzRyRx(1.0, 3.0, 2.0);
|
||||||
Pose3 pose3(rt3, pt3);
|
Pose3 pose3(rt3, pt3);
|
||||||
|
|
@ -189,7 +208,6 @@ PinholeCamera<Cal3_S2> cam1(pose3, cal1);
|
||||||
StereoCamera cam2(pose3, cal4ptr);
|
StereoCamera cam2(pose3, cal4ptr);
|
||||||
StereoPoint2 spt(1.0, 2.0, 3.0);
|
StereoPoint2 spt(1.0, 2.0, 3.0);
|
||||||
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
TEST (Serialization, text_geometry) {
|
TEST (Serialization, text_geometry) {
|
||||||
EXPECT(equalsObj<gtsam::Point2>(Point2(1.0, 2.0)));
|
EXPECT(equalsObj<gtsam::Point2>(Point2(1.0, 2.0)));
|
||||||
|
|
@ -232,6 +250,25 @@ TEST (Serialization, xml_geometry) {
|
||||||
EXPECT(equalsXML(spt));
|
EXPECT(equalsXML(spt));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
typedef PinholeCamera<Cal3_S2> PinholeCal3S2;
|
||||||
|
typedef PinholeCamera<Cal3DS2> PinholeCal3DS2;
|
||||||
|
typedef PinholeCamera<Cal3Bundler> PinholeCal3Bundler;
|
||||||
|
|
||||||
|
typedef TypedSymbol<Cal3_S2,'a'> PinholeCal3S2Key;
|
||||||
|
typedef TypedSymbol<Cal3DS2,'s'> PinholeCal3DS2Key;
|
||||||
|
typedef TypedSymbol<Cal3Bundler,'d'> PinholeCal3BundlerKey;
|
||||||
|
|
||||||
|
TEST (Serialization, TemplatedValues) {
|
||||||
|
Values values;
|
||||||
|
values.insert(PinholeCal3S2Key(0), PinholeCal3S2(pose3, cal1));
|
||||||
|
values.insert(PinholeCal3DS2Key(5), PinholeCal3DS2(pose3, cal2));
|
||||||
|
values.insert(PinholeCal3BundlerKey(47), PinholeCal3Bundler(pose3, cal3));
|
||||||
|
values.insert(PinholeCal3S2Key(5), PinholeCal3S2(pose3, cal1));
|
||||||
|
EXPECT(equalsObj(values));
|
||||||
|
EXPECT(equalsXML(values));
|
||||||
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
// Export Noisemodels
|
// Export Noisemodels
|
||||||
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained");
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained");
|
||||||
|
|
@ -437,13 +474,10 @@ TEST (Serialization, gaussianISAM) {
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
/* Create GUIDs for factors in simulated2D */
|
/* Create GUIDs for factors in simulated2D */
|
||||||
BOOST_CLASS_EXPORT_GUID(simulated2D::Prior, "gtsam::simulated2D::Prior" );
|
BOOST_CLASS_EXPORT_GUID(simulated2D::Prior, "gtsam::simulated2D::Prior" )
|
||||||
BOOST_CLASS_EXPORT_GUID(simulated2D::Odometry, "gtsam::simulated2D::Odometry" );
|
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")
|
||||||
BOOST_CLASS_EXPORT(gtsam::Point2)
|
|
||||||
BOOST_CLASS_EXPORT(gtsam::Point3)
|
|
||||||
BOOST_CLASS_EXPORT(gtsam::Pose2)
|
|
||||||
BOOST_CLASS_EXPORT(gtsam::Pose3)
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
TEST (Serialization, smallExample) {
|
TEST (Serialization, smallExample) {
|
||||||
using namespace example;
|
using namespace example;
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue