fix Unit3 and EssentialMatrix serialization

release/4.3a0
Jing Dong 2015-01-19 12:11:21 -05:00
parent 7382f38de4
commit f8e8729c8d
2 changed files with 21 additions and 1 deletions

View File

@ -155,7 +155,13 @@ private:
template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) {
ar & BOOST_SERIALIZATION_NVP(p_);
ar & BOOST_SERIALIZATION_NVP(B_);
// homebrew serialize Eigen Matrix
ar & boost::serialization::make_nvp("B11", (*B_)(0,0));
ar & boost::serialization::make_nvp("B12", (*B_)(0,1));
ar & boost::serialization::make_nvp("B21", (*B_)(1,0));
ar & boost::serialization::make_nvp("B22", (*B_)(1,1));
ar & boost::serialization::make_nvp("B31", (*B_)(2,0));
ar & boost::serialization::make_nvp("B32", (*B_)(2,1));
}
/// @}

View File

@ -19,6 +19,8 @@
#include <gtsam/geometry/Point2.h>
#include <gtsam/geometry/Point3.h>
#include <gtsam/geometry/Pose2.h>
#include <gtsam/geometry/Unit3.h>
#include <gtsam/geometry/EssentialMatrix.h>
#include <gtsam/geometry/Cal3_S2.h>
#include <gtsam/geometry/Cal3_S2Stereo.h>
#include <gtsam/geometry/CalibratedCamera.h>
@ -41,6 +43,9 @@ static Point3 pt3(1.0, 2.0, 3.0);
static Rot3 rt3 = Rot3::RzRyRx(1.0, 3.0, 2.0);
static Pose3 pose3(rt3, pt3);
static Unit3 unit3(1.0, 2.1, 3.4);
static EssentialMatrix ematrix(rt3, unit3);
static Cal3_S2 cal1(1.0, 2.0, 0.3, 0.1, 0.5);
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);
@ -59,6 +64,9 @@ TEST (Serialization, text_geometry) {
EXPECT(equalsObj<gtsam::Pose2>(Pose2(1.0, 2.0, 0.3)));
EXPECT(equalsObj<gtsam::Rot2>(Rot2::fromDegrees(30.0)));
EXPECT(equalsObj<gtsam::Unit3>(Unit3(1.0, 2.1, 3.4)));
EXPECT(equalsObj<gtsam::EssentialMatrix>(EssentialMatrix(rt3, unit3)));
EXPECT(equalsObj(pt3));
EXPECT(equalsObj<gtsam::Rot3>(rt3));
EXPECT(equalsObj<gtsam::Pose3>(Pose3(rt3, pt3)));
@ -81,6 +89,9 @@ TEST (Serialization, xml_geometry) {
EXPECT(equalsXML<gtsam::Pose2>(Pose2(1.0, 2.0, 0.3)));
EXPECT(equalsXML<gtsam::Rot2>(Rot2::fromDegrees(30.0)));
EXPECT(equalsXML<gtsam::Unit3>(Unit3(1.0, 2.1, 3.4)));
EXPECT(equalsXML<gtsam::EssentialMatrix>(EssentialMatrix(rt3, unit3)));
EXPECT(equalsXML<gtsam::Point3>(pt3));
EXPECT(equalsXML<gtsam::Rot3>(rt3));
EXPECT(equalsXML<gtsam::Pose3>(Pose3(rt3, pt3)));
@ -102,6 +113,9 @@ TEST (Serialization, binary_geometry) {
EXPECT(equalsBinary<gtsam::Pose2>(Pose2(1.0, 2.0, 0.3)));
EXPECT(equalsBinary<gtsam::Rot2>(Rot2::fromDegrees(30.0)));
EXPECT(equalsBinary<gtsam::Unit3>(Unit3(1.0, 2.1, 3.4)));
EXPECT(equalsBinary<gtsam::EssentialMatrix>(EssentialMatrix(rt3, unit3)));
EXPECT(equalsBinary<gtsam::Point3>(pt3));
EXPECT(equalsBinary<gtsam::Rot3>(rt3));
EXPECT(equalsBinary<gtsam::Pose3>(Pose3(rt3, pt3)));