fixed serialization tests
parent
c6ae119414
commit
52ec4f0784
|
@ -72,22 +72,22 @@ typedef NoiseModelFactor1<Pose> NM1;
|
|||
typedef NoiseModelFactor2<Pose,Pose> NM2;
|
||||
typedef BearingRangeFactor<Pose,Point2> BR;
|
||||
|
||||
BOOST_CLASS_EXPORT(Value);
|
||||
BOOST_CLASS_EXPORT(Pose);
|
||||
BOOST_CLASS_EXPORT(Rot2);
|
||||
BOOST_CLASS_EXPORT(Point2);
|
||||
BOOST_CLASS_EXPORT(NonlinearFactor);
|
||||
BOOST_CLASS_EXPORT(NoiseModelFactor);
|
||||
BOOST_CLASS_EXPORT(NM1);
|
||||
BOOST_CLASS_EXPORT(NM2);
|
||||
BOOST_CLASS_EXPORT(BetweenFactor<Pose>);
|
||||
BOOST_CLASS_EXPORT(PriorFactor<Pose>);
|
||||
BOOST_CLASS_EXPORT(BR);
|
||||
BOOST_CLASS_EXPORT(noiseModel::Base);
|
||||
BOOST_CLASS_EXPORT(noiseModel::Isotropic);
|
||||
BOOST_CLASS_EXPORT(noiseModel::Gaussian);
|
||||
BOOST_CLASS_EXPORT(noiseModel::Diagonal);
|
||||
BOOST_CLASS_EXPORT(noiseModel::Unit);
|
||||
GTSAM_VALUE_EXPORT(Value);
|
||||
GTSAM_VALUE_EXPORT(Pose);
|
||||
GTSAM_VALUE_EXPORT(Rot2);
|
||||
GTSAM_VALUE_EXPORT(Point2);
|
||||
GTSAM_VALUE_EXPORT(NonlinearFactor);
|
||||
GTSAM_VALUE_EXPORT(NoiseModelFactor);
|
||||
GTSAM_VALUE_EXPORT(NM1);
|
||||
GTSAM_VALUE_EXPORT(NM2);
|
||||
GTSAM_VALUE_EXPORT(BetweenFactor<Pose>);
|
||||
GTSAM_VALUE_EXPORT(PriorFactor<Pose>);
|
||||
GTSAM_VALUE_EXPORT(BR);
|
||||
GTSAM_VALUE_EXPORT(noiseModel::Base);
|
||||
GTSAM_VALUE_EXPORT(noiseModel::Isotropic);
|
||||
GTSAM_VALUE_EXPORT(noiseModel::Gaussian);
|
||||
GTSAM_VALUE_EXPORT(noiseModel::Diagonal);
|
||||
GTSAM_VALUE_EXPORT(noiseModel::Unit);
|
||||
|
||||
double chi2_red(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& config) {
|
||||
// Compute degrees of freedom (observations - variables)
|
||||
|
|
|
@ -253,6 +253,9 @@ public:
|
|||
ar & boost::serialization::make_nvp("value", value_);
|
||||
}
|
||||
|
||||
/// use this macro instead of BOOST_CLASS_EXPORT for GenericValues
|
||||
#define GTSAM_VALUE_EXPORT(Type) BOOST_CLASS_EXPORT(GenericValue<Type>)
|
||||
|
||||
};
|
||||
|
||||
// define Value::cast here since now GenericValue has been declared
|
||||
|
|
|
@ -168,7 +168,8 @@ namespace gtsam {
|
|||
* */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & ar, const unsigned int version) {}
|
||||
void serialize(ARCHIVE & ar, const unsigned int version) {
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
|
|
|
@ -149,6 +149,8 @@ V preconditionedConjugateGradient(const S &system, const V &initial, const Conju
|
|||
<< ", alpha = " << alpha
|
||||
<< ", beta = " << beta
|
||||
<< ", ||r||^2 = " << currentGamma
|
||||
// << "\nx =\n" << estimate
|
||||
// << "\nr =\n" << residual
|
||||
<< std::endl;
|
||||
}
|
||||
if (parameters.verbosity() >= ConjugateGradientParameters::COMPLEXITY )
|
||||
|
|
|
@ -32,14 +32,14 @@ using namespace gtsam::serializationTestHelpers;
|
|||
|
||||
/* ************************************************************************* */
|
||||
// Export all classes derived from Value
|
||||
BOOST_CLASS_EXPORT(gtsam::Cal3_S2);
|
||||
BOOST_CLASS_EXPORT(gtsam::Cal3Bundler);
|
||||
BOOST_CLASS_EXPORT(gtsam::Point3);
|
||||
BOOST_CLASS_EXPORT(gtsam::Pose3);
|
||||
BOOST_CLASS_EXPORT(gtsam::Rot3);
|
||||
BOOST_CLASS_EXPORT(gtsam::PinholeCamera<Cal3_S2>);
|
||||
BOOST_CLASS_EXPORT(gtsam::PinholeCamera<Cal3DS2>);
|
||||
BOOST_CLASS_EXPORT(gtsam::PinholeCamera<Cal3Bundler>);
|
||||
GTSAM_VALUE_EXPORT(gtsam::Cal3_S2);
|
||||
GTSAM_VALUE_EXPORT(gtsam::Cal3Bundler);
|
||||
GTSAM_VALUE_EXPORT(gtsam::Point3);
|
||||
GTSAM_VALUE_EXPORT(gtsam::Pose3);
|
||||
GTSAM_VALUE_EXPORT(gtsam::Rot3);
|
||||
GTSAM_VALUE_EXPORT(gtsam::PinholeCamera<Cal3_S2>);
|
||||
GTSAM_VALUE_EXPORT(gtsam::PinholeCamera<Cal3DS2>);
|
||||
GTSAM_VALUE_EXPORT(gtsam::PinholeCamera<Cal3Bundler>);
|
||||
|
||||
namespace detail {
|
||||
template<class T> struct pack {
|
||||
|
@ -62,27 +62,21 @@ static Cal3DS2 cal2(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0);
|
|||
static Cal3Bundler cal3(1.0, 2.0, 3.0);
|
||||
|
||||
TEST (Serialization, TemplatedValues) {
|
||||
std::cout << __LINE__ << std::endl;
|
||||
EXPECT(equalsObj(pt3));
|
||||
std::cout << __LINE__ << std::endl;
|
||||
GenericValue<Point3> chv1(pt3);
|
||||
std::cout << __LINE__ << std::endl;
|
||||
EXPECT(equalsObj(chv1));
|
||||
std::cout << __LINE__ << std::endl;
|
||||
PinholeCal3S2 pc(pose3,cal1);
|
||||
EXPECT(equalsObj(pc));
|
||||
std::cout << __LINE__ << std::endl;
|
||||
|
||||
Values values;
|
||||
values.insert(1,pt3);
|
||||
std::cout << __LINE__ << std::endl;
|
||||
|
||||
EXPECT(equalsObj(values));
|
||||
std::cout << __LINE__ << std::endl;
|
||||
values.insert(Symbol('a',0), PinholeCal3S2(pose3, cal1));
|
||||
values.insert(Symbol('s',5), PinholeCal3DS2(pose3, cal2));
|
||||
values.insert(Symbol('d',47), PinholeCal3Bundler(pose3, cal3));
|
||||
values.insert(Symbol('a',5), PinholeCal3S2(pose3, cal1));
|
||||
EXPECT(equalsObj(values));
|
||||
std::cout << __LINE__ << std::endl;
|
||||
EXPECT(equalsXML(values));
|
||||
EXPECT(equalsBinary(values));
|
||||
}
|
||||
|
|
|
@ -117,21 +117,21 @@ 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);
|
||||
GTSAM_VALUE_EXPORT(gtsam::LieVector);
|
||||
GTSAM_VALUE_EXPORT(gtsam::LieMatrix);
|
||||
GTSAM_VALUE_EXPORT(gtsam::Point2);
|
||||
GTSAM_VALUE_EXPORT(gtsam::StereoPoint2);
|
||||
GTSAM_VALUE_EXPORT(gtsam::Point3);
|
||||
GTSAM_VALUE_EXPORT(gtsam::Rot2);
|
||||
GTSAM_VALUE_EXPORT(gtsam::Rot3);
|
||||
GTSAM_VALUE_EXPORT(gtsam::Pose2);
|
||||
GTSAM_VALUE_EXPORT(gtsam::Pose3);
|
||||
GTSAM_VALUE_EXPORT(gtsam::Cal3_S2);
|
||||
GTSAM_VALUE_EXPORT(gtsam::Cal3DS2);
|
||||
GTSAM_VALUE_EXPORT(gtsam::Cal3_S2Stereo);
|
||||
GTSAM_VALUE_EXPORT(gtsam::CalibratedCamera);
|
||||
GTSAM_VALUE_EXPORT(gtsam::SimpleCamera);
|
||||
GTSAM_VALUE_EXPORT(gtsam::StereoCamera);
|
||||
|
||||
/* Create GUIDs for factors */
|
||||
/* ************************************************************************* */
|
||||
|
|
|
@ -87,18 +87,19 @@ TEST(PCGSolver, simpleLinearSystem) {
|
|||
simpleGFG += JacobianFactor(0, (Matrix(2,2)<< 1, 0, 0, 1).finished(), (Vector(2) << 0, 0).finished(), unit2);
|
||||
simpleGFG += JacobianFactor(1, (Matrix(2,2)<< 1, 0, 0, 1).finished(), (Vector(2) << 0, 0).finished(), unit2);
|
||||
simpleGFG += JacobianFactor(2, (Matrix(2,2)<< 1, 0, 0, 1).finished(), (Vector(2) << 0, 0).finished(), unit2);
|
||||
simpleGFG.print("system");
|
||||
|
||||
// Expected solution
|
||||
VectorValues expectedSolution;
|
||||
expectedSolution.insert(0, (Vector(2) << 0.100498, -0.196756).finished());
|
||||
expectedSolution.insert(2, (Vector(2) << -0.0990413, -0.0980577).finished());
|
||||
expectedSolution.insert(1, (Vector(2) << -0.0973252, 0.100582).finished());
|
||||
//expectedSolution.print("Expected");
|
||||
expectedSolution.print("Expected");
|
||||
|
||||
// Solve the system using direct method
|
||||
VectorValues deltaDirect = simpleGFG.optimize();
|
||||
EXPECT(assert_equal(expectedSolution, deltaDirect, 1e-5));
|
||||
//deltaDirect.print("Direct");
|
||||
deltaDirect.print("Direct");
|
||||
|
||||
// Solve the system using Preconditioned Conjugate Gradient solver
|
||||
// Common PCG parameters
|
||||
|
@ -106,19 +107,19 @@ TEST(PCGSolver, simpleLinearSystem) {
|
|||
pcg->setMaxIterations(500);
|
||||
pcg->setEpsilon_abs(0.0);
|
||||
pcg->setEpsilon_rel(0.0);
|
||||
//pcg->setVerbosity("ERROR");
|
||||
pcg->setVerbosity("ERROR");
|
||||
|
||||
// With Dummy preconditioner
|
||||
pcg->preconditioner_ = boost::make_shared<gtsam::DummyPreconditionerParameters>();
|
||||
VectorValues deltaPCGDummy = PCGSolver(*pcg).optimize(simpleGFG);
|
||||
EXPECT(assert_equal(expectedSolution, deltaPCGDummy, 1e-5));
|
||||
//deltaPCGDummy.print("PCG Dummy");
|
||||
deltaPCGDummy.print("PCG Dummy");
|
||||
|
||||
// With Block-Jacobi preconditioner
|
||||
pcg->preconditioner_ = boost::make_shared<gtsam::BlockJacobiPreconditionerParameters>();
|
||||
VectorValues deltaPCGJacobi = PCGSolver(*pcg).optimize(simpleGFG);
|
||||
EXPECT(assert_equal(expectedSolution, deltaPCGJacobi, 1e-5));
|
||||
//deltaPCGJacobi.print("PCG Jacobi");
|
||||
deltaPCGJacobi.print("PCG Jacobi");
|
||||
|
||||
}
|
||||
|
||||
|
|
|
@ -148,21 +148,21 @@ 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);
|
||||
GTSAM_VALUE_EXPORT(gtsam::LieVector);
|
||||
GTSAM_VALUE_EXPORT(gtsam::LieMatrix);
|
||||
GTSAM_VALUE_EXPORT(gtsam::Point2);
|
||||
GTSAM_VALUE_EXPORT(gtsam::StereoPoint2);
|
||||
GTSAM_VALUE_EXPORT(gtsam::Point3);
|
||||
GTSAM_VALUE_EXPORT(gtsam::Rot2);
|
||||
GTSAM_VALUE_EXPORT(gtsam::Rot3);
|
||||
GTSAM_VALUE_EXPORT(gtsam::Pose2);
|
||||
GTSAM_VALUE_EXPORT(gtsam::Pose3);
|
||||
GTSAM_VALUE_EXPORT(gtsam::Cal3_S2);
|
||||
GTSAM_VALUE_EXPORT(gtsam::Cal3DS2);
|
||||
GTSAM_VALUE_EXPORT(gtsam::Cal3_S2Stereo);
|
||||
GTSAM_VALUE_EXPORT(gtsam::CalibratedCamera);
|
||||
GTSAM_VALUE_EXPORT(gtsam::SimpleCamera);
|
||||
GTSAM_VALUE_EXPORT(gtsam::StereoCamera);
|
||||
|
||||
/* Create GUIDs for factors */
|
||||
/* ************************************************************************* */
|
||||
|
|
|
@ -39,20 +39,20 @@ typedef NoiseModelFactor1<Pose> NM1;
|
|||
typedef NoiseModelFactor2<Pose,Pose> NM2;
|
||||
typedef BearingRangeFactor<Pose,Point2> BR;
|
||||
|
||||
BOOST_CLASS_EXPORT(Value);
|
||||
BOOST_CLASS_EXPORT(Pose);
|
||||
BOOST_CLASS_EXPORT(NonlinearFactor);
|
||||
BOOST_CLASS_EXPORT(NoiseModelFactor);
|
||||
BOOST_CLASS_EXPORT(NM1);
|
||||
BOOST_CLASS_EXPORT(NM2);
|
||||
BOOST_CLASS_EXPORT(BetweenFactor<Pose>);
|
||||
BOOST_CLASS_EXPORT(PriorFactor<Pose>);
|
||||
BOOST_CLASS_EXPORT(BR);
|
||||
BOOST_CLASS_EXPORT(noiseModel::Base);
|
||||
BOOST_CLASS_EXPORT(noiseModel::Isotropic);
|
||||
BOOST_CLASS_EXPORT(noiseModel::Gaussian);
|
||||
BOOST_CLASS_EXPORT(noiseModel::Diagonal);
|
||||
BOOST_CLASS_EXPORT(noiseModel::Unit);
|
||||
GTSAM_VALUE_EXPORT(Value);
|
||||
GTSAM_VALUE_EXPORT(Pose);
|
||||
GTSAM_VALUE_EXPORT(NonlinearFactor);
|
||||
GTSAM_VALUE_EXPORT(NoiseModelFactor);
|
||||
GTSAM_VALUE_EXPORT(NM1);
|
||||
GTSAM_VALUE_EXPORT(NM2);
|
||||
GTSAM_VALUE_EXPORT(BetweenFactor<Pose>);
|
||||
GTSAM_VALUE_EXPORT(PriorFactor<Pose>);
|
||||
GTSAM_VALUE_EXPORT(BR);
|
||||
GTSAM_VALUE_EXPORT(noiseModel::Base);
|
||||
GTSAM_VALUE_EXPORT(noiseModel::Isotropic);
|
||||
GTSAM_VALUE_EXPORT(noiseModel::Gaussian);
|
||||
GTSAM_VALUE_EXPORT(noiseModel::Diagonal);
|
||||
GTSAM_VALUE_EXPORT(noiseModel::Unit);
|
||||
|
||||
double chi2_red(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& config) {
|
||||
// Compute degrees of freedom (observations - variables)
|
||||
|
|
Loading…
Reference in New Issue