Added serialization unit tests for binary files
parent
f68e301458
commit
07c4c95f18
|
@ -36,6 +36,8 @@
|
||||||
#include <boost/archive/text_iarchive.hpp>
|
#include <boost/archive/text_iarchive.hpp>
|
||||||
#include <boost/archive/xml_iarchive.hpp>
|
#include <boost/archive/xml_iarchive.hpp>
|
||||||
#include <boost/archive/xml_oarchive.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;
|
||||||
|
@ -146,4 +148,55 @@ 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
|
||||||
|
template<class T>
|
||||||
|
void roundtripBinary(const T& input, T& output) {
|
||||||
|
// Serialize
|
||||||
|
std::string serialized = serializeBinary<T>(input);
|
||||||
|
if (verbose) std::cout << serialized << std::endl << std::endl;
|
||||||
|
|
||||||
|
// De-serialize
|
||||||
|
deserializeBinary(serialized, output);
|
||||||
|
}
|
||||||
|
|
||||||
|
// This version requires equality operator
|
||||||
|
template<class T>
|
||||||
|
bool equalityBinary(const T& input = T()) {
|
||||||
|
T output;
|
||||||
|
roundtripBinary<T>(input,output);
|
||||||
|
return input==output;
|
||||||
|
}
|
||||||
|
|
||||||
|
// This version requires equals
|
||||||
|
template<class T>
|
||||||
|
bool equalsBinary(const T& input = T()) {
|
||||||
|
T output;
|
||||||
|
roundtripBinary<T>(input,output);
|
||||||
|
return input.equals(output);
|
||||||
|
}
|
||||||
|
|
||||||
|
// This version is for pointers
|
||||||
|
template<class T>
|
||||||
|
bool equalsDereferencedBinary(const T& input = T()) {
|
||||||
|
T output;
|
||||||
|
roundtripBinary<T>(input,output);
|
||||||
|
return input->equals(*output);
|
||||||
|
}
|
||||||
|
|
||||||
} }
|
} }
|
||||||
|
|
|
@ -43,6 +43,7 @@ TEST (Serialization, FastList) {
|
||||||
|
|
||||||
EXPECT(equality(list));
|
EXPECT(equality(list));
|
||||||
EXPECT(equalityXML(list));
|
EXPECT(equalityXML(list));
|
||||||
|
EXPECT(equalityBinary(list));
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
@ -54,6 +55,7 @@ TEST (Serialization, FastMap) {
|
||||||
|
|
||||||
EXPECT(equality(map));
|
EXPECT(equality(map));
|
||||||
EXPECT(equalityXML(map));
|
EXPECT(equalityXML(map));
|
||||||
|
EXPECT(equalityBinary(map));
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
@ -65,6 +67,7 @@ TEST (Serialization, FastSet) {
|
||||||
|
|
||||||
EXPECT(equality(set));
|
EXPECT(equality(set));
|
||||||
EXPECT(equalityXML(set));
|
EXPECT(equalityXML(set));
|
||||||
|
EXPECT(equalityBinary(set));
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
@ -76,6 +79,7 @@ TEST (Serialization, FastVector) {
|
||||||
|
|
||||||
EXPECT(equality(vector));
|
EXPECT(equality(vector));
|
||||||
EXPECT(equalityXML(vector));
|
EXPECT(equalityXML(vector));
|
||||||
|
EXPECT(equalityBinary(vector));
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
@ -85,6 +89,9 @@ TEST (Serialization, matrix_vector) {
|
||||||
|
|
||||||
EXPECT(equalityXML<Vector>(Vector_(4, 1.0, 2.0, 3.0, 4.0)));
|
EXPECT(equalityXML<Vector>(Vector_(4, 1.0, 2.0, 3.0, 4.0)));
|
||||||
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)));
|
||||||
|
|
||||||
|
EXPECT(equalityBinary<Vector>(Vector_(4, 1.0, 2.0, 3.0, 4.0)));
|
||||||
|
EXPECT(equalityBinary<Matrix>(Matrix_(2, 2, 1.0, 2.0, 3.0, 4.0)));
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
|
|
@ -93,6 +93,27 @@ TEST (Serialization, xml_geometry) {
|
||||||
EXPECT(equalsXML(spt));
|
EXPECT(equalsXML(spt));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
TEST (Serialization, binary_geometry) {
|
||||||
|
EXPECT(equalsBinary<gtsam::Point2>(Point2(1.0, 2.0)));
|
||||||
|
EXPECT(equalsBinary<gtsam::Pose2>(Pose2(1.0, 2.0, 0.3)));
|
||||||
|
EXPECT(equalsBinary<gtsam::Rot2>(Rot2::fromDegrees(30.0)));
|
||||||
|
|
||||||
|
EXPECT(equalsBinary<gtsam::Point3>(pt3));
|
||||||
|
EXPECT(equalsBinary<gtsam::Rot3>(rt3));
|
||||||
|
EXPECT(equalsBinary<gtsam::Pose3>(Pose3(rt3, pt3)));
|
||||||
|
|
||||||
|
EXPECT(equalsBinary(cal1));
|
||||||
|
EXPECT(equalsBinary(cal2));
|
||||||
|
EXPECT(equalsBinary(cal3));
|
||||||
|
EXPECT(equalsBinary(cal4));
|
||||||
|
EXPECT(equalsBinary(cal5));
|
||||||
|
|
||||||
|
EXPECT(equalsBinary(cam1));
|
||||||
|
EXPECT(equalsBinary(cam2));
|
||||||
|
EXPECT(equalsBinary(spt));
|
||||||
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
|
int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
|
|
@ -38,6 +38,7 @@ TEST (Serialization, symbolic_graph) {
|
||||||
|
|
||||||
EXPECT(equalsObj(sfg));
|
EXPECT(equalsObj(sfg));
|
||||||
EXPECT(equalsXML(sfg));
|
EXPECT(equalsXML(sfg));
|
||||||
|
EXPECT(equalsBinary(sfg));
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
@ -53,6 +54,7 @@ TEST (Serialization, symbolic_bn) {
|
||||||
|
|
||||||
EXPECT(equalsObj(sbn));
|
EXPECT(equalsObj(sbn));
|
||||||
EXPECT(equalsXML(sbn));
|
EXPECT(equalsXML(sbn));
|
||||||
|
EXPECT(equalsBinary(sbn));
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
@ -78,6 +80,7 @@ TEST (Serialization, symbolic_bayes_tree ) {
|
||||||
|
|
||||||
EXPECT(equalsObj(bayesTree));
|
EXPECT(equalsObj(bayesTree));
|
||||||
EXPECT(equalsXML(bayesTree));
|
EXPECT(equalsXML(bayesTree));
|
||||||
|
EXPECT(equalsBinary(bayesTree));
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
|
|
@ -56,20 +56,25 @@ static noiseModel::Unit::shared_ptr unit3 = noiseModel::Unit::Create(3);
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
TEST (Serialization, noiseModels) {
|
TEST (Serialization, noiseModels) {
|
||||||
// tests using pointers to the derived class
|
// tests using pointers to the derived class
|
||||||
EXPECT( equalsDereferenced<noiseModel::Diagonal::shared_ptr>(diag3));
|
EXPECT(equalsDereferenced<noiseModel::Diagonal::shared_ptr>(diag3));
|
||||||
EXPECT(equalsDereferencedXML<noiseModel::Diagonal::shared_ptr>(diag3));
|
EXPECT(equalsDereferencedXML<noiseModel::Diagonal::shared_ptr>(diag3));
|
||||||
|
EXPECT(equalsDereferencedBinary<noiseModel::Diagonal::shared_ptr>(diag3));
|
||||||
|
|
||||||
EXPECT( equalsDereferenced<noiseModel::Gaussian::shared_ptr>(gaussian3));
|
EXPECT(equalsDereferenced<noiseModel::Gaussian::shared_ptr>(gaussian3));
|
||||||
EXPECT(equalsDereferencedXML<noiseModel::Gaussian::shared_ptr>(gaussian3));
|
EXPECT(equalsDereferencedXML<noiseModel::Gaussian::shared_ptr>(gaussian3));
|
||||||
|
EXPECT(equalsDereferencedBinary<noiseModel::Gaussian::shared_ptr>(gaussian3));
|
||||||
|
|
||||||
EXPECT( equalsDereferenced<noiseModel::Isotropic::shared_ptr>(iso3));
|
EXPECT(equalsDereferenced<noiseModel::Isotropic::shared_ptr>(iso3));
|
||||||
EXPECT(equalsDereferencedXML<noiseModel::Isotropic::shared_ptr>(iso3));
|
EXPECT(equalsDereferencedXML<noiseModel::Isotropic::shared_ptr>(iso3));
|
||||||
|
EXPECT(equalsDereferencedBinary<noiseModel::Isotropic::shared_ptr>(iso3));
|
||||||
|
|
||||||
EXPECT( equalsDereferenced<noiseModel::Constrained::shared_ptr>(constrained3));
|
EXPECT(equalsDereferenced<noiseModel::Constrained::shared_ptr>(constrained3));
|
||||||
EXPECT(equalsDereferencedXML<noiseModel::Constrained::shared_ptr>(constrained3));
|
EXPECT(equalsDereferencedXML<noiseModel::Constrained::shared_ptr>(constrained3));
|
||||||
|
EXPECT(equalsDereferencedBinary<noiseModel::Constrained::shared_ptr>(constrained3));
|
||||||
|
|
||||||
EXPECT( equalsDereferenced<noiseModel::Unit::shared_ptr>(unit3));
|
EXPECT(equalsDereferenced<noiseModel::Unit::shared_ptr>(unit3));
|
||||||
EXPECT(equalsDereferencedXML<noiseModel::Unit::shared_ptr>(unit3));
|
EXPECT(equalsDereferencedXML<noiseModel::Unit::shared_ptr>(unit3));
|
||||||
|
EXPECT(equalsDereferencedBinary<noiseModel::Unit::shared_ptr>(unit3));
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
@ -77,36 +82,46 @@ TEST (Serialization, SharedNoiseModel_noiseModels) {
|
||||||
SharedNoiseModel diag3_sg = diag3;
|
SharedNoiseModel diag3_sg = diag3;
|
||||||
EXPECT(equalsDereferenced<SharedNoiseModel>(diag3_sg));
|
EXPECT(equalsDereferenced<SharedNoiseModel>(diag3_sg));
|
||||||
EXPECT(equalsDereferencedXML<SharedNoiseModel>(diag3_sg));
|
EXPECT(equalsDereferencedXML<SharedNoiseModel>(diag3_sg));
|
||||||
|
EXPECT(equalsDereferencedBinary<SharedNoiseModel>(diag3_sg));
|
||||||
|
|
||||||
EXPECT(equalsDereferenced<SharedNoiseModel>(diag3));
|
EXPECT(equalsDereferenced<SharedNoiseModel>(diag3));
|
||||||
EXPECT(equalsDereferencedXML<SharedNoiseModel>(diag3));
|
EXPECT(equalsDereferencedXML<SharedNoiseModel>(diag3));
|
||||||
|
EXPECT(equalsDereferencedBinary<SharedNoiseModel>(diag3));
|
||||||
|
|
||||||
EXPECT(equalsDereferenced<SharedNoiseModel>(iso3));
|
EXPECT(equalsDereferenced<SharedNoiseModel>(iso3));
|
||||||
EXPECT(equalsDereferencedXML<SharedNoiseModel>(iso3));
|
EXPECT(equalsDereferencedXML<SharedNoiseModel>(iso3));
|
||||||
|
EXPECT(equalsDereferencedBinary<SharedNoiseModel>(iso3));
|
||||||
|
|
||||||
EXPECT(equalsDereferenced<SharedNoiseModel>(gaussian3));
|
EXPECT(equalsDereferenced<SharedNoiseModel>(gaussian3));
|
||||||
EXPECT(equalsDereferencedXML<SharedNoiseModel>(gaussian3));
|
EXPECT(equalsDereferencedXML<SharedNoiseModel>(gaussian3));
|
||||||
|
EXPECT(equalsDereferencedBinary<SharedNoiseModel>(gaussian3));
|
||||||
|
|
||||||
EXPECT(equalsDereferenced<SharedNoiseModel>(unit3));
|
EXPECT(equalsDereferenced<SharedNoiseModel>(unit3));
|
||||||
EXPECT(equalsDereferencedXML<SharedNoiseModel>(unit3));
|
EXPECT(equalsDereferencedXML<SharedNoiseModel>(unit3));
|
||||||
|
EXPECT(equalsDereferencedBinary<SharedNoiseModel>(unit3));
|
||||||
|
|
||||||
EXPECT(equalsDereferenced<SharedNoiseModel>(constrained3));
|
EXPECT(equalsDereferenced<SharedNoiseModel>(constrained3));
|
||||||
EXPECT(equalsDereferencedXML<SharedNoiseModel>(constrained3));
|
EXPECT(equalsDereferencedXML<SharedNoiseModel>(constrained3));
|
||||||
|
EXPECT(equalsDereferencedBinary<SharedNoiseModel>(constrained3));
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
TEST (Serialization, SharedDiagonal_noiseModels) {
|
TEST (Serialization, SharedDiagonal_noiseModels) {
|
||||||
EXPECT(equalsDereferenced<SharedDiagonal>(diag3));
|
EXPECT(equalsDereferenced<SharedDiagonal>(diag3));
|
||||||
EXPECT(equalsDereferencedXML<SharedDiagonal>(diag3));
|
EXPECT(equalsDereferencedXML<SharedDiagonal>(diag3));
|
||||||
|
EXPECT(equalsDereferencedBinary<SharedDiagonal>(diag3));
|
||||||
|
|
||||||
EXPECT(equalsDereferenced<SharedDiagonal>(iso3));
|
EXPECT(equalsDereferenced<SharedDiagonal>(iso3));
|
||||||
EXPECT(equalsDereferencedXML<SharedDiagonal>(iso3));
|
EXPECT(equalsDereferencedXML<SharedDiagonal>(iso3));
|
||||||
|
EXPECT(equalsDereferencedBinary<SharedDiagonal>(iso3));
|
||||||
|
|
||||||
EXPECT(equalsDereferenced<SharedDiagonal>(unit3));
|
EXPECT(equalsDereferenced<SharedDiagonal>(unit3));
|
||||||
EXPECT(equalsDereferencedXML<SharedDiagonal>(unit3));
|
EXPECT(equalsDereferencedXML<SharedDiagonal>(unit3));
|
||||||
|
EXPECT(equalsDereferencedBinary<SharedDiagonal>(unit3));
|
||||||
|
|
||||||
EXPECT(equalsDereferenced<SharedDiagonal>(constrained3));
|
EXPECT(equalsDereferenced<SharedDiagonal>(constrained3));
|
||||||
EXPECT(equalsDereferencedXML<SharedDiagonal>(constrained3));
|
EXPECT(equalsDereferencedXML<SharedDiagonal>(constrained3));
|
||||||
|
EXPECT(equalsDereferencedBinary<SharedDiagonal>(constrained3));
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
@ -126,6 +141,7 @@ TEST (Serialization, linear_factors) {
|
||||||
values.insert(2, Vector_(2, 4.0,5.0));
|
values.insert(2, Vector_(2, 4.0,5.0));
|
||||||
EXPECT(equalsObj<VectorValues>(values));
|
EXPECT(equalsObj<VectorValues>(values));
|
||||||
EXPECT(equalsXML<VectorValues>(values));
|
EXPECT(equalsXML<VectorValues>(values));
|
||||||
|
EXPECT(equalsBinary<VectorValues>(values));
|
||||||
|
|
||||||
Index i1 = 4, i2 = 7;
|
Index i1 = 4, i2 = 7;
|
||||||
Matrix A1 = eye(3), A2 = -1.0 * eye(3);
|
Matrix A1 = eye(3), A2 = -1.0 * eye(3);
|
||||||
|
@ -134,10 +150,12 @@ TEST (Serialization, linear_factors) {
|
||||||
JacobianFactor jacobianfactor(i1, A1, i2, A2, b, model);
|
JacobianFactor jacobianfactor(i1, A1, i2, A2, b, model);
|
||||||
EXPECT(equalsObj(jacobianfactor));
|
EXPECT(equalsObj(jacobianfactor));
|
||||||
EXPECT(equalsXML(jacobianfactor));
|
EXPECT(equalsXML(jacobianfactor));
|
||||||
|
EXPECT(equalsBinary(jacobianfactor));
|
||||||
|
|
||||||
HessianFactor hessianfactor(jacobianfactor);
|
HessianFactor hessianfactor(jacobianfactor);
|
||||||
EXPECT(equalsObj(hessianfactor));
|
EXPECT(equalsObj(hessianfactor));
|
||||||
EXPECT(equalsXML(hessianfactor));
|
EXPECT(equalsXML(hessianfactor));
|
||||||
|
EXPECT(equalsBinary(hessianfactor));
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
@ -150,6 +168,7 @@ TEST (Serialization, gaussian_conditional) {
|
||||||
|
|
||||||
EXPECT(equalsObj(cg));
|
EXPECT(equalsObj(cg));
|
||||||
EXPECT(equalsXML(cg));
|
EXPECT(equalsXML(cg));
|
||||||
|
EXPECT(equalsBinary(cg));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -63,6 +63,7 @@ TEST (Serialization, TemplatedValues) {
|
||||||
values.insert(Symbol('a',5), PinholeCal3S2(pose3, cal1));
|
values.insert(Symbol('a',5), PinholeCal3S2(pose3, cal1));
|
||||||
EXPECT(equalsObj(values));
|
EXPECT(equalsObj(values));
|
||||||
EXPECT(equalsXML(values));
|
EXPECT(equalsXML(values));
|
||||||
|
EXPECT(equalsBinary(values));
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
|
|
@ -232,13 +232,16 @@ TEST (Serialization, smallExample_linear) {
|
||||||
GaussianFactorGraph fg = createGaussianFactorGraph(ordering);
|
GaussianFactorGraph fg = createGaussianFactorGraph(ordering);
|
||||||
EXPECT(equalsObj(ordering));
|
EXPECT(equalsObj(ordering));
|
||||||
EXPECT(equalsXML(ordering));
|
EXPECT(equalsXML(ordering));
|
||||||
|
EXPECT(equalsBinary(ordering));
|
||||||
|
|
||||||
EXPECT(equalsObj(fg));
|
EXPECT(equalsObj(fg));
|
||||||
EXPECT(equalsXML(fg));
|
EXPECT(equalsXML(fg));
|
||||||
|
EXPECT(equalsBinary(fg));
|
||||||
|
|
||||||
GaussianBayesNet cbn = createSmallGaussianBayesNet();
|
GaussianBayesNet cbn = createSmallGaussianBayesNet();
|
||||||
EXPECT(equalsObj(cbn));
|
EXPECT(equalsObj(cbn));
|
||||||
EXPECT(equalsXML(cbn));
|
EXPECT(equalsXML(cbn));
|
||||||
|
EXPECT(equalsBinary(cbn));
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
@ -252,6 +255,7 @@ TEST (Serialization, gaussianISAM) {
|
||||||
|
|
||||||
EXPECT(equalsObj(isam));
|
EXPECT(equalsObj(isam));
|
||||||
EXPECT(equalsXML(isam));
|
EXPECT(equalsXML(isam));
|
||||||
|
EXPECT(equalsBinary(isam));
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
@ -267,9 +271,11 @@ TEST (Serialization, smallExample_nonlinear) {
|
||||||
Values c1 = createValues();
|
Values c1 = createValues();
|
||||||
EXPECT(equalsObj(nfg));
|
EXPECT(equalsObj(nfg));
|
||||||
EXPECT(equalsXML(nfg));
|
EXPECT(equalsXML(nfg));
|
||||||
|
EXPECT(equalsBinary(nfg));
|
||||||
|
|
||||||
EXPECT(equalsObj(c1));
|
EXPECT(equalsObj(c1));
|
||||||
EXPECT(equalsXML(c1));
|
EXPECT(equalsXML(c1));
|
||||||
|
EXPECT(equalsBinary(c1));
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
@ -586,9 +592,79 @@ TEST (Serialization, factors) {
|
||||||
EXPECT(equalsXML<GeneralSFMFactor2Cal3_S2>(generalSFMFactor2Cal3_S2));
|
EXPECT(equalsXML<GeneralSFMFactor2Cal3_S2>(generalSFMFactor2Cal3_S2));
|
||||||
|
|
||||||
EXPECT(equalsXML<GenericStereoFactor3D>(genericStereoFactor3D));
|
EXPECT(equalsXML<GenericStereoFactor3D>(genericStereoFactor3D));
|
||||||
|
|
||||||
|
|
||||||
|
// binary
|
||||||
|
EXPECT(equalsBinary<Symbol>(a01));
|
||||||
|
EXPECT(equalsBinary<Symbol>(b02));
|
||||||
|
EXPECT(equalsBinary<Values>(values));
|
||||||
|
EXPECT(equalsBinary<NonlinearFactorGraph>(graph));
|
||||||
|
|
||||||
|
EXPECT(equalsBinary<PriorFactorLieVector>(priorFactorLieVector));
|
||||||
|
EXPECT(equalsBinary<PriorFactorLieMatrix>(priorFactorLieMatrix));
|
||||||
|
EXPECT(equalsBinary<PriorFactorPoint2>(priorFactorPoint2));
|
||||||
|
EXPECT(equalsBinary<PriorFactorStereoPoint2>(priorFactorStereoPoint2));
|
||||||
|
EXPECT(equalsBinary<PriorFactorPoint3>(priorFactorPoint3));
|
||||||
|
EXPECT(equalsBinary<PriorFactorRot2>(priorFactorRot2));
|
||||||
|
EXPECT(equalsBinary<PriorFactorRot3>(priorFactorRot3));
|
||||||
|
EXPECT(equalsBinary<PriorFactorPose2>(priorFactorPose2));
|
||||||
|
EXPECT(equalsBinary<PriorFactorPose3>(priorFactorPose3));
|
||||||
|
EXPECT(equalsBinary<PriorFactorCal3_S2>(priorFactorCal3_S2));
|
||||||
|
EXPECT(equalsBinary<PriorFactorCal3DS2>(priorFactorCal3DS2));
|
||||||
|
EXPECT(equalsBinary<PriorFactorCalibratedCamera>(priorFactorCalibratedCamera));
|
||||||
|
EXPECT(equalsBinary<PriorFactorSimpleCamera>(priorFactorSimpleCamera));
|
||||||
|
EXPECT(equalsBinary<PriorFactorStereoCamera>(priorFactorStereoCamera));
|
||||||
|
|
||||||
|
EXPECT(equalsBinary<BetweenFactorLieVector>(betweenFactorLieVector));
|
||||||
|
EXPECT(equalsBinary<BetweenFactorLieMatrix>(betweenFactorLieMatrix));
|
||||||
|
EXPECT(equalsBinary<BetweenFactorPoint2>(betweenFactorPoint2));
|
||||||
|
EXPECT(equalsBinary<BetweenFactorPoint3>(betweenFactorPoint3));
|
||||||
|
EXPECT(equalsBinary<BetweenFactorRot2>(betweenFactorRot2));
|
||||||
|
EXPECT(equalsBinary<BetweenFactorRot3>(betweenFactorRot3));
|
||||||
|
EXPECT(equalsBinary<BetweenFactorPose2>(betweenFactorPose2));
|
||||||
|
EXPECT(equalsBinary<BetweenFactorPose3>(betweenFactorPose3));
|
||||||
|
|
||||||
|
EXPECT(equalsBinary<NonlinearEqualityLieVector>(nonlinearEqualityLieVector));
|
||||||
|
EXPECT(equalsBinary<NonlinearEqualityLieMatrix>(nonlinearEqualityLieMatrix));
|
||||||
|
EXPECT(equalsBinary<NonlinearEqualityPoint2>(nonlinearEqualityPoint2));
|
||||||
|
EXPECT(equalsBinary<NonlinearEqualityStereoPoint2>(nonlinearEqualityStereoPoint2));
|
||||||
|
EXPECT(equalsBinary<NonlinearEqualityPoint3>(nonlinearEqualityPoint3));
|
||||||
|
EXPECT(equalsBinary<NonlinearEqualityRot2>(nonlinearEqualityRot2));
|
||||||
|
EXPECT(equalsBinary<NonlinearEqualityRot3>(nonlinearEqualityRot3));
|
||||||
|
EXPECT(equalsBinary<NonlinearEqualityPose2>(nonlinearEqualityPose2));
|
||||||
|
EXPECT(equalsBinary<NonlinearEqualityPose3>(nonlinearEqualityPose3));
|
||||||
|
EXPECT(equalsBinary<NonlinearEqualityCal3_S2>(nonlinearEqualityCal3_S2));
|
||||||
|
EXPECT(equalsBinary<NonlinearEqualityCal3DS2>(nonlinearEqualityCal3DS2));
|
||||||
|
EXPECT(equalsBinary<NonlinearEqualityCalibratedCamera>(nonlinearEqualityCalibratedCamera));
|
||||||
|
EXPECT(equalsBinary<NonlinearEqualitySimpleCamera>(nonlinearEqualitySimpleCamera));
|
||||||
|
EXPECT(equalsBinary<NonlinearEqualityStereoCamera>(nonlinearEqualityStereoCamera));
|
||||||
|
|
||||||
|
EXPECT(equalsBinary<RangeFactorPosePoint2>(rangeFactorPosePoint2));
|
||||||
|
EXPECT(equalsBinary<RangeFactorPosePoint3>(rangeFactorPosePoint3));
|
||||||
|
EXPECT(equalsBinary<RangeFactorPose2>(rangeFactorPose2));
|
||||||
|
EXPECT(equalsBinary<RangeFactorPose3>(rangeFactorPose3));
|
||||||
|
EXPECT(equalsBinary<RangeFactorCalibratedCameraPoint>(rangeFactorCalibratedCameraPoint));
|
||||||
|
EXPECT(equalsBinary<RangeFactorSimpleCameraPoint>(rangeFactorSimpleCameraPoint));
|
||||||
|
EXPECT(equalsBinary<RangeFactorCalibratedCamera>(rangeFactorCalibratedCamera));
|
||||||
|
EXPECT(equalsBinary<RangeFactorSimpleCamera>(rangeFactorSimpleCamera));
|
||||||
|
|
||||||
|
EXPECT(equalsBinary<BearingFactor2D>(bearingFactor2D));
|
||||||
|
|
||||||
|
EXPECT(equalsBinary<BearingRangeFactor2D>(bearingRangeFactor2D));
|
||||||
|
|
||||||
|
EXPECT(equalsBinary<GenericProjectionFactorCal3_S2>(genericProjectionFactorCal3_S2));
|
||||||
|
EXPECT(equalsBinary<GenericProjectionFactorCal3DS2>(genericProjectionFactorCal3DS2));
|
||||||
|
|
||||||
|
EXPECT(equalsBinary<GeneralSFMFactorCal3_S2>(generalSFMFactorCal3_S2));
|
||||||
|
|
||||||
|
EXPECT(equalsBinary<GeneralSFMFactor2Cal3_S2>(generalSFMFactor2Cal3_S2));
|
||||||
|
|
||||||
|
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