/* ---------------------------------------------------------------------------- * 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 testSerializationSLAM.cpp * @brief test serialization * @author Richard Roberts * @date Feb 7, 2012 */ #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include using namespace std; using namespace gtsam; using namespace gtsam::serializationTestHelpers; // Creating as many permutations of factors as possible typedef PriorFactor PriorFactorPoint2; typedef PriorFactor PriorFactorStereoPoint2; typedef PriorFactor PriorFactorPoint3; typedef PriorFactor PriorFactorRot2; typedef PriorFactor PriorFactorRot3; typedef PriorFactor PriorFactorPose2; typedef PriorFactor PriorFactorPose3; typedef PriorFactor PriorFactorCal3_S2; typedef PriorFactor PriorFactorCal3DS2; typedef PriorFactor PriorFactorCalibratedCamera; typedef PriorFactor PriorFactorPinholeCameraCal3_S2; typedef PriorFactor PriorFactorStereoCamera; typedef BetweenFactor BetweenFactorPoint2; typedef BetweenFactor BetweenFactorPoint3; typedef BetweenFactor BetweenFactorRot2; typedef BetweenFactor BetweenFactorRot3; typedef BetweenFactor BetweenFactorPose2; typedef BetweenFactor BetweenFactorPose3; typedef NonlinearEquality NonlinearEqualityPoint2; typedef NonlinearEquality NonlinearEqualityStereoPoint2; typedef NonlinearEquality NonlinearEqualityPoint3; typedef NonlinearEquality NonlinearEqualityRot2; typedef NonlinearEquality NonlinearEqualityRot3; typedef NonlinearEquality NonlinearEqualityPose2; typedef NonlinearEquality NonlinearEqualityPose3; typedef NonlinearEquality NonlinearEqualityCal3_S2; typedef NonlinearEquality NonlinearEqualityCal3DS2; typedef NonlinearEquality NonlinearEqualityCalibratedCamera; typedef NonlinearEquality NonlinearEqualityPinholeCameraCal3_S2; typedef NonlinearEquality NonlinearEqualityStereoCamera; typedef RangeFactor RangeFactor2D; typedef RangeFactor RangeFactor3D; typedef RangeFactor RangeFactorPose2; typedef RangeFactor RangeFactorPose3; typedef RangeFactor RangeFactorCalibratedCameraPoint; typedef RangeFactor RangeFactorSimpleCameraPoint; typedef RangeFactor RangeFactorPinholeCameraCal3_S2Point; typedef RangeFactor RangeFactorCalibratedCamera; typedef RangeFactor RangeFactorSimpleCamera; typedef RangeFactor RangeFactorPinholeCameraCal3_S2; typedef BearingRangeFactor BearingRangeFactor2D; typedef BearingRangeFactor BearingRangeFactor3D; typedef GenericProjectionFactor GenericProjectionFactorCal3_S2; typedef GenericProjectionFactor GenericProjectionFactorCal3DS2; typedef gtsam::GeneralSFMFactor GeneralSFMFactorCal3_S2; //typedef gtsam::GeneralSFMFactor GeneralSFMFactorCal3DS2; typedef gtsam::GeneralSFMFactor2 GeneralSFMFactor2Cal3_S2; typedef gtsam::GenericStereoFactor GenericStereoFactor3D; // Convenience for named keys using symbol_shorthand::X; using symbol_shorthand::L; /* 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::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::SharedDiagonal, "gtsam_SharedDiagonal"); /* Create GUIDs for geometry */ /* ************************************************************************* */ 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::PinholeCameraCal3_S2); GTSAM_VALUE_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(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(PriorFactorStereoCamera, "gtsam::PriorFactorStereoCamera"); 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(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(NonlinearEqualityStereoCamera, "gtsam::NonlinearEqualityStereoCamera"); BOOST_CLASS_EXPORT_GUID(RangeFactor2D, "gtsam::RangeFactor2D"); BOOST_CLASS_EXPORT_GUID(RangeFactor3D, "gtsam::RangeFactor3D"); 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(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"); /* ************************************************************************* */ TEST (testSerializationSLAM, smallExample_linear) { using namespace example; Ordering ordering; ordering += X(1),X(2),L(1); EXPECT(equalsObj(ordering)); EXPECT(equalsXML(ordering)); EXPECT(equalsBinary(ordering)); GaussianFactorGraph fg = createGaussianFactorGraph(); EXPECT(equalsObj(fg)); EXPECT(equalsXML(fg)); EXPECT(equalsBinary(fg)); GaussianBayesNet cbn = createSmallGaussianBayesNet(); EXPECT(equalsObj(cbn)); EXPECT(equalsXML(cbn)); EXPECT(equalsBinary(cbn)); } /* ************************************************************************* */ TEST (testSerializationSLAM, gaussianISAM) { using namespace example; GaussianFactorGraph smoother = createSmoother(7); GaussianBayesTree bayesTree = *smoother.eliminateMultifrontal(); GaussianISAM isam(bayesTree); EXPECT(equalsObj(isam)); EXPECT(equalsXML(isam)); EXPECT(equalsBinary(isam)); } /* ************************************************************************* */ /* Create GUIDs for factors in simulated2D */ BOOST_CLASS_EXPORT_GUID(simulated2D::Prior, "gtsam::simulated2D::Prior" ) BOOST_CLASS_EXPORT_GUID(simulated2D::Odometry, "gtsam::simulated2D::Odometry" ) BOOST_CLASS_EXPORT_GUID(simulated2D::Measurement, "gtsam::simulated2D::Measurement") /* ************************************************************************* */ TEST (testSerializationSLAM, smallExample_nonlinear) { using namespace example; NonlinearFactorGraph nfg = createNonlinearFactorGraph(); Values c1 = createValues(); EXPECT(equalsObj(nfg)); EXPECT(equalsXML(nfg)); EXPECT(equalsBinary(nfg)); EXPECT(equalsObj(c1)); EXPECT(equalsXML(c1)); EXPECT(equalsBinary(c1)); } /* ************************************************************************* */ TEST (testSerializationSLAM, factors) { Point2 point2(1.0, 2.0); StereoPoint2 stereoPoint2(1.0, 2.0, 3.0); Point3 point3(1.0, 2.0, 3.0); Rot2 rot2(1.0); Rot3 rot3(Rot3::RzRyRx(1.0, 2.0, 3.0)); Pose2 pose2(rot2, point2); Pose3 pose3(rot3, point3); Cal3_S2 cal3_s2(1.0, 2.0, 3.0, 4.0, 5.0); Cal3DS2 cal3ds2(1.0, 2.0, 3.0, 4.0, 5.0,6.0, 7.0, 8.0, 9.0); Cal3_S2Stereo cal3_s2stereo(1.0, 2.0, 3.0, 4.0, 5.0, 1.0); CalibratedCamera calibratedCamera(pose3); PinholeCamera simpleCamera(pose3, cal3_s2); StereoCamera stereoCamera(pose3, boost::make_shared(cal3_s2stereo)); Symbol a01('a',1), a02('a',2), a03('a',3), a04('a',4), a05('a',5), a06('a',6), a07('a',7), a08('a',8), a09('a',9), a10('a',10), a11('a',11), a12('a',12), a13('a',13), a14('a',14), a15('a',15); Symbol b01('b',1), b02('b',2), b03('b',3), b04('b',4), b05('b',5), b06('b',6), b07('b',7), b08('b',8), b09('b',9), b10('b',10), b11('b',11), b12('b',12), b13('b',13), b14('b',14), b15('b',15); Values values; values.insert(a03, point2); values.insert(a04, stereoPoint2); values.insert(a05, point3); values.insert(a06, rot2); values.insert(a07, rot3); values.insert(a08, pose2); values.insert(a09, pose3); values.insert(a10, cal3_s2); values.insert(a11, cal3ds2); values.insert(a12, calibratedCamera); values.insert(a13, simpleCamera); values.insert(a14, stereoCamera); SharedNoiseModel model1 = noiseModel::Isotropic::Sigma(1, 0.3); SharedNoiseModel model2 = noiseModel::Isotropic::Sigma(2, 0.3); SharedNoiseModel model3 = noiseModel::Isotropic::Sigma(3, 0.3); SharedNoiseModel model4 = noiseModel::Isotropic::Sigma(4, 0.3); SharedNoiseModel model5 = noiseModel::Isotropic::Sigma(5, 0.3); SharedNoiseModel model6 = noiseModel::Isotropic::Sigma(6, 0.3); SharedNoiseModel model9 = noiseModel::Isotropic::Sigma(9, 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)); PriorFactorPoint2 priorFactorPoint2(a03, point2, model2); PriorFactorStereoPoint2 priorFactorStereoPoint2(a04, stereoPoint2, model3); PriorFactorPoint3 priorFactorPoint3(a05, point3, model3); PriorFactorRot2 priorFactorRot2(a06, rot2, model1); PriorFactorRot3 priorFactorRot3(a07, rot3, model3); PriorFactorPose2 priorFactorPose2(a08, pose2, model3); PriorFactorPose3 priorFactorPose3(a09, pose3, model6); PriorFactorCal3_S2 priorFactorCal3_S2(a10, cal3_s2, model5); PriorFactorCal3DS2 priorFactorCal3DS2(a11, cal3ds2, model9); PriorFactorCalibratedCamera priorFactorCalibratedCamera(a12, calibratedCamera, model6); PriorFactorStereoCamera priorFactorStereoCamera(a14, stereoCamera, model11); BetweenFactorPoint2 betweenFactorPoint2(a03, b03, point2, model2); BetweenFactorPoint3 betweenFactorPoint3(a05, b05, point3, model3); BetweenFactorRot2 betweenFactorRot2(a06, b06, rot2, model1); BetweenFactorRot3 betweenFactorRot3(a07, b07, rot3, model3); BetweenFactorPose2 betweenFactorPose2(a08, b08, pose2, model3); BetweenFactorPose3 betweenFactorPose3(a09, b09, pose3, model6); NonlinearEqualityPoint2 nonlinearEqualityPoint2(a03, point2); NonlinearEqualityStereoPoint2 nonlinearEqualityStereoPoint2(a04, stereoPoint2); NonlinearEqualityPoint3 nonlinearEqualityPoint3(a05, point3); NonlinearEqualityRot2 nonlinearEqualityRot2(a06, rot2); NonlinearEqualityRot3 nonlinearEqualityRot3(a07, rot3); NonlinearEqualityPose2 nonlinearEqualityPose2(a08, pose2); NonlinearEqualityPose3 nonlinearEqualityPose3(a09, pose3); NonlinearEqualityCal3_S2 nonlinearEqualityCal3_S2(a10, cal3_s2); NonlinearEqualityCal3DS2 nonlinearEqualityCal3DS2(a11, cal3ds2); NonlinearEqualityCalibratedCamera nonlinearEqualityCalibratedCamera(a12, calibratedCamera); NonlinearEqualityStereoCamera nonlinearEqualityStereoCamera(a14, stereoCamera); RangeFactor2D rangeFactor2D(a08, a03, 2.0, model1); RangeFactor3D rangeFactor3D(a09, a05, 2.0, model1); RangeFactorPose2 rangeFactorPose2(a08, b08, 2.0, model1); RangeFactorPose3 rangeFactorPose3(a09, b09, 2.0, model1); RangeFactorCalibratedCameraPoint rangeFactorCalibratedCameraPoint(a12, a05, 2.0, model1); RangeFactorSimpleCameraPoint rangeFactorSimpleCameraPoint(a13, a05, 2.0, model1); RangeFactorCalibratedCamera rangeFactorCalibratedCamera(a12, b12, 2.0, model1); RangeFactorSimpleCamera rangeFactorSimpleCamera(a13, b13, 2.0, model1); BearingRangeFactor2D bearingRangeFactor2D(a08, a03, rot2, 2.0, model2); GenericProjectionFactorCal3_S2 genericProjectionFactorCal3_S2(point2, model2, a09, a05, boost::make_shared(cal3_s2)); GenericProjectionFactorCal3DS2 genericProjectionFactorCal3DS2(point2, model2, a09, a05, boost::make_shared(cal3ds2)); GeneralSFMFactorCal3_S2 generalSFMFactorCal3_S2(point2, model2, a13, a05); GeneralSFMFactor2Cal3_S2 generalSFMFactor2Cal3_S2(point2, model2, a09, a05, a10); GenericStereoFactor3D genericStereoFactor3D(stereoPoint2, model3, a09, a05, boost::make_shared(cal3_s2stereo)); NonlinearFactorGraph graph; graph += priorFactorPoint2; graph += priorFactorStereoPoint2; graph += priorFactorPoint3; graph += priorFactorRot2; graph += priorFactorRot3; graph += priorFactorPose2; graph += priorFactorPose3; graph += priorFactorCal3_S2; graph += priorFactorCal3DS2; graph += priorFactorCalibratedCamera; graph += priorFactorStereoCamera; graph += betweenFactorPoint2; graph += betweenFactorPoint3; graph += betweenFactorRot2; graph += betweenFactorRot3; graph += betweenFactorPose2; graph += betweenFactorPose3; graph += nonlinearEqualityPoint2; graph += nonlinearEqualityStereoPoint2; graph += nonlinearEqualityPoint3; graph += nonlinearEqualityRot2; graph += nonlinearEqualityRot3; graph += nonlinearEqualityPose2; graph += nonlinearEqualityPose3; graph += nonlinearEqualityCal3_S2; graph += nonlinearEqualityCal3DS2; graph += nonlinearEqualityCalibratedCamera; graph += nonlinearEqualityStereoCamera; graph += rangeFactor2D; graph += rangeFactor3D; graph += rangeFactorPose2; graph += rangeFactorPose3; graph += rangeFactorCalibratedCameraPoint; graph += rangeFactorSimpleCameraPoint; graph += rangeFactorCalibratedCamera; graph += rangeFactorSimpleCamera; graph += bearingRangeFactor2D; graph += genericProjectionFactorCal3_S2; graph += genericProjectionFactorCal3DS2; graph += generalSFMFactorCal3_S2; graph += generalSFMFactor2Cal3_S2; graph += genericStereoFactor3D; // text EXPECT(equalsObj(a01)); EXPECT(equalsObj(b02)); EXPECT(equalsObj(values)); EXPECT(equalsObj(graph)); EXPECT(equalsObj(priorFactorPoint2)); EXPECT(equalsObj(priorFactorStereoPoint2)); EXPECT(equalsObj(priorFactorPoint3)); EXPECT(equalsObj(priorFactorRot2)); EXPECT(equalsObj(priorFactorRot3)); EXPECT(equalsObj(priorFactorPose2)); EXPECT(equalsObj(priorFactorPose3)); EXPECT(equalsObj(priorFactorCal3_S2)); EXPECT(equalsObj(priorFactorCal3DS2)); EXPECT(equalsObj(priorFactorCalibratedCamera)); EXPECT(equalsObj(priorFactorStereoCamera)); EXPECT(equalsObj(betweenFactorPoint2)); EXPECT(equalsObj(betweenFactorPoint3)); EXPECT(equalsObj(betweenFactorRot2)); EXPECT(equalsObj(betweenFactorRot3)); EXPECT(equalsObj(betweenFactorPose2)); EXPECT(equalsObj(betweenFactorPose3)); EXPECT(equalsObj(nonlinearEqualityPoint2)); EXPECT(equalsObj(nonlinearEqualityStereoPoint2)); EXPECT(equalsObj(nonlinearEqualityPoint3)); EXPECT(equalsObj(nonlinearEqualityRot2)); EXPECT(equalsObj(nonlinearEqualityRot3)); EXPECT(equalsObj(nonlinearEqualityPose2)); EXPECT(equalsObj(nonlinearEqualityPose3)); EXPECT(equalsObj(nonlinearEqualityCal3_S2)); EXPECT(equalsObj(nonlinearEqualityCal3DS2)); EXPECT(equalsObj(nonlinearEqualityCalibratedCamera)); EXPECT(equalsObj(nonlinearEqualityStereoCamera)); EXPECT(equalsObj(rangeFactor2D)); EXPECT(equalsObj(rangeFactor3D)); EXPECT(equalsObj(rangeFactorPose2)); EXPECT(equalsObj(rangeFactorPose3)); EXPECT(equalsObj(rangeFactorCalibratedCameraPoint)); EXPECT(equalsObj(rangeFactorSimpleCameraPoint)); EXPECT(equalsObj(rangeFactorCalibratedCamera)); EXPECT(equalsObj(rangeFactorSimpleCamera)); EXPECT(equalsObj(bearingRangeFactor2D)); EXPECT(equalsObj(genericProjectionFactorCal3_S2)); EXPECT(equalsObj(genericProjectionFactorCal3DS2)); EXPECT(equalsObj(generalSFMFactorCal3_S2)); EXPECT(equalsObj(generalSFMFactor2Cal3_S2)); EXPECT(equalsObj(genericStereoFactor3D)); // xml EXPECT(equalsXML(a01)); EXPECT(equalsXML(b02)); EXPECT(equalsXML(values)); EXPECT(equalsXML(graph)); EXPECT(equalsXML(priorFactorPoint2)); EXPECT(equalsXML(priorFactorStereoPoint2)); EXPECT(equalsXML(priorFactorPoint3)); EXPECT(equalsXML(priorFactorRot2)); EXPECT(equalsXML(priorFactorRot3)); EXPECT(equalsXML(priorFactorPose2)); EXPECT(equalsXML(priorFactorPose3)); EXPECT(equalsXML(priorFactorCal3_S2)); EXPECT(equalsXML(priorFactorCal3DS2)); EXPECT(equalsXML(priorFactorCalibratedCamera)); EXPECT(equalsXML(priorFactorStereoCamera)); EXPECT(equalsXML(betweenFactorPoint2)); EXPECT(equalsXML(betweenFactorPoint3)); EXPECT(equalsXML(betweenFactorRot2)); EXPECT(equalsXML(betweenFactorRot3)); EXPECT(equalsXML(betweenFactorPose2)); EXPECT(equalsXML(betweenFactorPose3)); EXPECT(equalsXML(nonlinearEqualityPoint2)); EXPECT(equalsXML(nonlinearEqualityStereoPoint2)); EXPECT(equalsXML(nonlinearEqualityPoint3)); EXPECT(equalsXML(nonlinearEqualityRot2)); EXPECT(equalsXML(nonlinearEqualityRot3)); EXPECT(equalsXML(nonlinearEqualityPose2)); EXPECT(equalsXML(nonlinearEqualityPose3)); EXPECT(equalsXML(nonlinearEqualityCal3_S2)); EXPECT(equalsXML(nonlinearEqualityCal3DS2)); EXPECT(equalsXML(nonlinearEqualityCalibratedCamera)); EXPECT(equalsXML(nonlinearEqualityStereoCamera)); EXPECT(equalsXML(rangeFactor2D)); EXPECT(equalsXML(rangeFactor3D)); EXPECT(equalsXML(rangeFactorPose2)); EXPECT(equalsXML(rangeFactorPose3)); EXPECT(equalsXML(rangeFactorCalibratedCameraPoint)); EXPECT(equalsXML(rangeFactorSimpleCameraPoint)); EXPECT(equalsXML(rangeFactorCalibratedCamera)); EXPECT(equalsXML(rangeFactorSimpleCamera)); EXPECT(equalsXML(bearingRangeFactor2D)); EXPECT(equalsXML(genericProjectionFactorCal3_S2)); EXPECT(equalsXML(genericProjectionFactorCal3DS2)); EXPECT(equalsXML(generalSFMFactorCal3_S2)); EXPECT(equalsXML(generalSFMFactor2Cal3_S2)); EXPECT(equalsXML(genericStereoFactor3D)); // binary EXPECT(equalsBinary(a01)); EXPECT(equalsBinary(b02)); EXPECT(equalsBinary(values)); EXPECT(equalsBinary(graph)); EXPECT(equalsBinary(priorFactorPoint2)); EXPECT(equalsBinary(priorFactorStereoPoint2)); EXPECT(equalsBinary(priorFactorPoint3)); EXPECT(equalsBinary(priorFactorRot2)); EXPECT(equalsBinary(priorFactorRot3)); EXPECT(equalsBinary(priorFactorPose2)); EXPECT(equalsBinary(priorFactorPose3)); EXPECT(equalsBinary(priorFactorCal3_S2)); EXPECT(equalsBinary(priorFactorCal3DS2)); EXPECT(equalsBinary(priorFactorCalibratedCamera)); EXPECT(equalsBinary(priorFactorStereoCamera)); EXPECT(equalsBinary(betweenFactorPoint2)); EXPECT(equalsBinary(betweenFactorPoint3)); EXPECT(equalsBinary(betweenFactorRot2)); EXPECT(equalsBinary(betweenFactorRot3)); EXPECT(equalsBinary(betweenFactorPose2)); EXPECT(equalsBinary(betweenFactorPose3)); EXPECT(equalsBinary(nonlinearEqualityPoint2)); EXPECT(equalsBinary(nonlinearEqualityStereoPoint2)); EXPECT(equalsBinary(nonlinearEqualityPoint3)); EXPECT(equalsBinary(nonlinearEqualityRot2)); EXPECT(equalsBinary(nonlinearEqualityRot3)); EXPECT(equalsBinary(nonlinearEqualityPose2)); EXPECT(equalsBinary(nonlinearEqualityPose3)); EXPECT(equalsBinary(nonlinearEqualityCal3_S2)); EXPECT(equalsBinary(nonlinearEqualityCal3DS2)); EXPECT(equalsBinary(nonlinearEqualityCalibratedCamera)); EXPECT(equalsBinary(nonlinearEqualityStereoCamera)); EXPECT(equalsBinary(rangeFactor2D)); EXPECT(equalsBinary(rangeFactor3D)); EXPECT(equalsBinary(rangeFactorPose2)); EXPECT(equalsBinary(rangeFactorPose3)); EXPECT(equalsBinary(rangeFactorCalibratedCameraPoint)); EXPECT(equalsBinary(rangeFactorSimpleCameraPoint)); EXPECT(equalsBinary(rangeFactorCalibratedCamera)); EXPECT(equalsBinary(rangeFactorSimpleCamera)); EXPECT(equalsBinary(bearingRangeFactor2D)); EXPECT(equalsBinary(genericProjectionFactorCal3_S2)); EXPECT(equalsBinary(genericProjectionFactorCal3DS2)); EXPECT(equalsBinary(generalSFMFactorCal3_S2)); EXPECT(equalsBinary(generalSFMFactor2Cal3_S2)); EXPECT(equalsBinary(genericStereoFactor3D)); } /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */