fixing xml serialization issues
							parent
							
								
									c46e3dbee6
								
							
						
					
					
						commit
						e0cda60b9b
					
				| 
						 | 
					@ -29,11 +29,10 @@
 | 
				
			||||||
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
 | 
					#include <gtsam/nonlinear/NonlinearFactorGraph.h>
 | 
				
			||||||
#include <gtsam/nonlinear/Values.h>
 | 
					#include <gtsam/nonlinear/Values.h>
 | 
				
			||||||
#include <gtsam/linear/NoiseModel.h>
 | 
					#include <gtsam/linear/NoiseModel.h>
 | 
				
			||||||
 | 
					#include <gtsam/base/serialization.h>
 | 
				
			||||||
#include <gtsam/base/Testable.h>
 | 
					#include <gtsam/base/Testable.h>
 | 
				
			||||||
#include <gtsam/base/types.h>
 | 
					#include <gtsam/base/types.h>
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					 | 
				
			||||||
#include <boost/serialization/vector.hpp>
 | 
					 | 
				
			||||||
#include <boost/smart_ptr/shared_ptr.hpp>
 | 
					#include <boost/smart_ptr/shared_ptr.hpp>
 | 
				
			||||||
#include <string>
 | 
					#include <string>
 | 
				
			||||||
#include <utility> // for pair
 | 
					#include <utility> // for pair
 | 
				
			||||||
| 
						 | 
					@ -218,94 +217,95 @@ typedef std::pair<size_t, Point2> SfmMeasurement;
 | 
				
			||||||
typedef std::pair<size_t, size_t> SiftIndex;
 | 
					typedef std::pair<size_t, size_t> SiftIndex;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
/// Define the structure for the 3D points
 | 
					/// Define the structure for the 3D points
 | 
				
			||||||
struct SfmTrack {
 | 
					class GTSAM_EXPORT SfmTrack {
 | 
				
			||||||
  SfmTrack(): p(0,0,0) {}
 | 
					  public:
 | 
				
			||||||
  SfmTrack(const gtsam::Point3& pt) : p(pt) {}
 | 
					    SfmTrack(): p(0,0,0) {}
 | 
				
			||||||
  Point3 p; ///< 3D position of the point
 | 
					    SfmTrack(const gtsam::Point3& pt) : p(pt) {}
 | 
				
			||||||
  float r, g, b; ///< RGB color of the 3D point
 | 
					    Point3 p; ///< 3D position of the point
 | 
				
			||||||
  std::vector<SfmMeasurement> measurements; ///< The 2D image projections (id,(u,v))
 | 
					    float r, g, b; ///< RGB color of the 3D point
 | 
				
			||||||
  std::vector<SiftIndex> siftIndices;
 | 
					    std::vector<SfmMeasurement> measurements; ///< The 2D image projections (id,(u,v))
 | 
				
			||||||
 | 
					    std::vector<SiftIndex> siftIndices;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  /// Total number of measurements in this track
 | 
					    /// Total number of measurements in this track
 | 
				
			||||||
  size_t number_measurements() const {
 | 
					    size_t number_measurements() const {
 | 
				
			||||||
    return measurements.size();
 | 
					      return measurements.size();
 | 
				
			||||||
  }
 | 
					    }
 | 
				
			||||||
  /// Get the measurement (camera index, Point2) at pose index `idx`
 | 
					    /// Get the measurement (camera index, Point2) at pose index `idx`
 | 
				
			||||||
  SfmMeasurement measurement(size_t idx) const {
 | 
					    SfmMeasurement measurement(size_t idx) const {
 | 
				
			||||||
    return measurements[idx];
 | 
					      return measurements[idx];
 | 
				
			||||||
  }
 | 
					    }
 | 
				
			||||||
  /// Get the SIFT feature index corresponding to the measurement at `idx`
 | 
					    /// Get the SIFT feature index corresponding to the measurement at `idx`
 | 
				
			||||||
  SiftIndex siftIndex(size_t idx) const {
 | 
					    SiftIndex siftIndex(size_t idx) const {
 | 
				
			||||||
    return siftIndices[idx];
 | 
					      return siftIndices[idx];
 | 
				
			||||||
  }
 | 
					    }
 | 
				
			||||||
  /// Get 3D point
 | 
					    /// Get 3D point
 | 
				
			||||||
  const Point3& point3() const {
 | 
					    const Point3& point3() const {
 | 
				
			||||||
    return p;
 | 
					      return p;
 | 
				
			||||||
  }
 | 
					    }
 | 
				
			||||||
  /// Add measurement (camera_idx, Point2) to track
 | 
					    /// Add measurement (camera_idx, Point2) to track
 | 
				
			||||||
  void add_measurement(size_t idx, const gtsam::Point2& m) {
 | 
					    void add_measurement(size_t idx, const gtsam::Point2& m) {
 | 
				
			||||||
    measurements.emplace_back(idx, m);
 | 
					      measurements.emplace_back(idx, m);
 | 
				
			||||||
  }
 | 
					 | 
				
			||||||
 | 
					 | 
				
			||||||
  /** Serialization function */
 | 
					 | 
				
			||||||
  friend class boost::serialization::access;
 | 
					 | 
				
			||||||
  template<class ARCHIVE>
 | 
					 | 
				
			||||||
  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
 | 
					 | 
				
			||||||
    ar & p;
 | 
					 | 
				
			||||||
    ar & r;
 | 
					 | 
				
			||||||
    ar & g;
 | 
					 | 
				
			||||||
    ar & b;
 | 
					 | 
				
			||||||
    ar & measurements;
 | 
					 | 
				
			||||||
    ar & siftIndices;
 | 
					 | 
				
			||||||
  }
 | 
					 | 
				
			||||||
 | 
					 | 
				
			||||||
  /// assert equality up to a tolerance
 | 
					 | 
				
			||||||
  bool equals(const SfmTrack &sfmTrack, double tol = 1e-9) const {
 | 
					 | 
				
			||||||
    // check the 3D point
 | 
					 | 
				
			||||||
    if (!p.isApprox(sfmTrack.p)) {
 | 
					 | 
				
			||||||
      return false;
 | 
					 | 
				
			||||||
    }
 | 
					    }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
    // check the RGB values
 | 
					    /** Serialization function */
 | 
				
			||||||
    if (r!=sfmTrack.r || g!=sfmTrack.g || b!=sfmTrack.b) {
 | 
					    friend class boost::serialization::access;
 | 
				
			||||||
      return false;
 | 
					    template<class ARCHIVE>
 | 
				
			||||||
 | 
					    void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
 | 
				
			||||||
 | 
					      ar & BOOST_SERIALIZATION_NVP(p);
 | 
				
			||||||
 | 
					      ar & BOOST_SERIALIZATION_NVP(r);
 | 
				
			||||||
 | 
					      ar & BOOST_SERIALIZATION_NVP(g);
 | 
				
			||||||
 | 
					      ar & BOOST_SERIALIZATION_NVP(b);
 | 
				
			||||||
 | 
					      ar & BOOST_SERIALIZATION_NVP(measurements);
 | 
				
			||||||
 | 
					      ar & BOOST_SERIALIZATION_NVP(siftIndices);
 | 
				
			||||||
    }
 | 
					    }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
    // compare size of vectors for measurements and siftIndices
 | 
					    /// assert equality up to a tolerance
 | 
				
			||||||
    if (number_measurements() != sfmTrack.number_measurements() ||
 | 
					    bool equals(const SfmTrack &sfmTrack, double tol = 1e-9) const {
 | 
				
			||||||
        siftIndices.size() != sfmTrack.siftIndices.size()) {
 | 
					      // check the 3D point
 | 
				
			||||||
      return false;
 | 
					      if (!p.isApprox(sfmTrack.p)) {
 | 
				
			||||||
    }
 | 
					 | 
				
			||||||
 | 
					 | 
				
			||||||
    // compare measurements (order sensitive)
 | 
					 | 
				
			||||||
    for (size_t idx = 0; idx < number_measurements(); ++idx) {
 | 
					 | 
				
			||||||
      SfmMeasurement measurement = measurements[idx];
 | 
					 | 
				
			||||||
      SfmMeasurement otherMeasurement = sfmTrack.measurements[idx];
 | 
					 | 
				
			||||||
 | 
					 | 
				
			||||||
      if (measurement.first != otherMeasurement.first ||
 | 
					 | 
				
			||||||
          !measurement.second.isApprox(otherMeasurement.second)) {
 | 
					 | 
				
			||||||
        return false;
 | 
					        return false;
 | 
				
			||||||
      }
 | 
					      }
 | 
				
			||||||
    }
 | 
					 | 
				
			||||||
 | 
					
 | 
				
			||||||
    // compare sift indices (order sensitive)
 | 
					      // check the RGB values
 | 
				
			||||||
    for (size_t idx = 0; idx < siftIndices.size(); ++idx) {
 | 
					      if (r!=sfmTrack.r || g!=sfmTrack.g || b!=sfmTrack.b) {
 | 
				
			||||||
      SiftIndex index = siftIndices[idx];
 | 
					 | 
				
			||||||
      SiftIndex otherIndex = sfmTrack.siftIndices[idx];
 | 
					 | 
				
			||||||
 | 
					 | 
				
			||||||
      if (index.first != otherIndex.first ||
 | 
					 | 
				
			||||||
          index.second != otherIndex.second) {
 | 
					 | 
				
			||||||
        return false;
 | 
					        return false;
 | 
				
			||||||
      }
 | 
					      }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					      // compare size of vectors for measurements and siftIndices
 | 
				
			||||||
 | 
					      if (number_measurements() != sfmTrack.number_measurements() ||
 | 
				
			||||||
 | 
					          siftIndices.size() != sfmTrack.siftIndices.size()) {
 | 
				
			||||||
 | 
					        return false;
 | 
				
			||||||
 | 
					      }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					      // compare measurements (order sensitive)
 | 
				
			||||||
 | 
					      for (size_t idx = 0; idx < number_measurements(); ++idx) {
 | 
				
			||||||
 | 
					        SfmMeasurement measurement = measurements[idx];
 | 
				
			||||||
 | 
					        SfmMeasurement otherMeasurement = sfmTrack.measurements[idx];
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					        if (measurement.first != otherMeasurement.first ||
 | 
				
			||||||
 | 
					            !measurement.second.isApprox(otherMeasurement.second)) {
 | 
				
			||||||
 | 
					          return false;
 | 
				
			||||||
 | 
					        }
 | 
				
			||||||
 | 
					      }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					      // compare sift indices (order sensitive)
 | 
				
			||||||
 | 
					      for (size_t idx = 0; idx < siftIndices.size(); ++idx) {
 | 
				
			||||||
 | 
					        SiftIndex index = siftIndices[idx];
 | 
				
			||||||
 | 
					        SiftIndex otherIndex = sfmTrack.siftIndices[idx];
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					        if (index.first != otherIndex.first ||
 | 
				
			||||||
 | 
					            index.second != otherIndex.second) {
 | 
				
			||||||
 | 
					          return false;
 | 
				
			||||||
 | 
					        }
 | 
				
			||||||
 | 
					      }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					      return true;
 | 
				
			||||||
    }
 | 
					    }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
    return true;
 | 
					    /// print
 | 
				
			||||||
  }
 | 
					    void print(const std::string& s = "") const {
 | 
				
			||||||
 | 
					      cout << "Track with " << measurements.size() << "measurements\n";
 | 
				
			||||||
  /// print
 | 
					    }
 | 
				
			||||||
  void print(const std::string& s = "") const {
 | 
					 | 
				
			||||||
    cout << "Track with " << measurements.size() << "measurements\n";
 | 
					 | 
				
			||||||
  }
 | 
					 | 
				
			||||||
};
 | 
					};
 | 
				
			||||||
 | 
					
 | 
				
			||||||
/* ************************************************************************* */
 | 
					/* ************************************************************************* */
 | 
				
			||||||
| 
						 | 
					@ -350,8 +350,8 @@ struct SfmData {
 | 
				
			||||||
  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 & cameras;
 | 
					    ar & BOOST_SERIALIZATION_NVP(cameras);
 | 
				
			||||||
    ar & tracks;
 | 
					    ar & BOOST_SERIALIZATION_NVP(tracks);
 | 
				
			||||||
  }
 | 
					  }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  /// @}
 | 
					  /// @}
 | 
				
			||||||
| 
						 | 
					
 | 
				
			||||||
| 
						 | 
					@ -26,19 +26,19 @@ using namespace gtsam;
 | 
				
			||||||
using namespace gtsam::serializationTestHelpers;
 | 
					using namespace gtsam::serializationTestHelpers;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
/* ************************************************************************* */
 | 
					/* ************************************************************************* */
 | 
				
			||||||
TEST(dataSet, sfmDataSerialization){
 | 
					TEST(dataSet, sfmDataSerialization) {
 | 
				
			||||||
  // Test the serialization of SfmData
 | 
					  // Test the serialization of SfmData
 | 
				
			||||||
  const string filename = findExampleDataFile("dubrovnik-3-7-pre");
 | 
					  const string filename = findExampleDataFile("dubrovnik-3-7-pre");
 | 
				
			||||||
  SfmData mydata;
 | 
					  SfmData mydata;
 | 
				
			||||||
  CHECK(readBAL(filename, mydata));
 | 
					  CHECK(readBAL(filename, mydata));
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  EXPECT(equalsObj(mydata));
 | 
					  EXPECT(equalsObj(mydata));
 | 
				
			||||||
  // EXPECT(equalsXML(mydata));
 | 
					  EXPECT(equalsXML(mydata));
 | 
				
			||||||
  // EXPECT(equalsBinary(mydata));
 | 
					  EXPECT(equalsBinary(mydata));
 | 
				
			||||||
}
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
/* ************************************************************************* */
 | 
					/* ************************************************************************* */
 | 
				
			||||||
TEST(dataSet, sfmTrackSerialization){
 | 
					TEST(dataSet, sfmTrackSerialization) {
 | 
				
			||||||
  // Test the serialization of SfmTrack
 | 
					  // Test the serialization of SfmTrack
 | 
				
			||||||
  const string filename = findExampleDataFile("dubrovnik-3-7-pre");
 | 
					  const string filename = findExampleDataFile("dubrovnik-3-7-pre");
 | 
				
			||||||
  SfmData mydata;
 | 
					  SfmData mydata;
 | 
				
			||||||
| 
						 | 
					@ -47,8 +47,8 @@ TEST(dataSet, sfmTrackSerialization){
 | 
				
			||||||
  SfmTrack track = mydata.track(0);
 | 
					  SfmTrack track = mydata.track(0);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  EXPECT(equalsObj(track));
 | 
					  EXPECT(equalsObj(track));
 | 
				
			||||||
  // EXPECT(equalsXML(track));
 | 
					  EXPECT(equalsXML(track));
 | 
				
			||||||
  // EXPECT(equalsBinary(track));
 | 
					  EXPECT(equalsBinary(track));
 | 
				
			||||||
}
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
/* ************************************************************************* */
 | 
					/* ************************************************************************* */
 | 
				
			||||||
| 
						 | 
					
 | 
				
			||||||
		Loading…
	
		Reference in New Issue