wrapped sfmtrack
							parent
							
								
									045780a151
								
							
						
					
					
						commit
						a68b0798f9
					
				| 
						 | 
				
			
			@ -2759,30 +2759,15 @@ virtual class EssentialMatrixFactor : gtsam::NoiseModelFactor {
 | 
			
		|||
};
 | 
			
		||||
 | 
			
		||||
#include <gtsam/slam/dataset.h>
 | 
			
		||||
class SfmMeasurement{
 | 
			
		||||
  SfmMeasurement();
 | 
			
		||||
  size_t i() const;
 | 
			
		||||
  Point2 j() const;
 | 
			
		||||
};
 | 
			
		||||
class SiftIndex{
 | 
			
		||||
  SiftIndex();
 | 
			
		||||
  size_t i() const;
 | 
			
		||||
  size_t j() const;
 | 
			
		||||
 };
 | 
			
		||||
class SfmMeasurements{
 | 
			
		||||
  SfmMeasurements();
 | 
			
		||||
 | 
			
		||||
};
 | 
			
		||||
 | 
			
		||||
class SfmTrack {
 | 
			
		||||
  SfmTrack();
 | 
			
		||||
  Point3 point3() const;
 | 
			
		||||
  size_t number_measurements() const;
 | 
			
		||||
  void setP(gtsam::Point3& p_);
 | 
			
		||||
  gtsam::SfmMeasurement measurement(size_t idx) const;
 | 
			
		||||
  gtsam::SiftIndex siftIndex(size_t idx) const;
 | 
			
		||||
  pair<size_t, gtsam::Point2> measurement(size_t idx) const;
 | 
			
		||||
  pair<size_t, size_t> siftIndex(size_t idx) const;
 | 
			
		||||
  void add_measurement(const pair<size_t, gtsam::Point2>& m);
 | 
			
		||||
  SfmMeasurements& measurements();
 | 
			
		||||
};
 | 
			
		||||
 | 
			
		||||
class SfmData {
 | 
			
		||||
| 
						 | 
				
			
			@ -2792,7 +2777,7 @@ class SfmData {
 | 
			
		|||
  gtsam::PinholeCamera<gtsam::Cal3Bundler> camera(size_t idx) const;
 | 
			
		||||
  gtsam::SfmTrack track(size_t idx) const;
 | 
			
		||||
  void add_track(const gtsam::SfmTrack& t) ;
 | 
			
		||||
  void add_camera(const gtsam::SfmCamer& cam);
 | 
			
		||||
  void add_camera(const gtsam::SfmCamera& cam);
 | 
			
		||||
};
 | 
			
		||||
 | 
			
		||||
gtsam::SfmData readBal(string filename);
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -228,7 +228,7 @@ struct SfmTrack {
 | 
			
		|||
    return measurements.size();
 | 
			
		||||
  }
 | 
			
		||||
  /// Set 3D point
 | 
			
		||||
  void setP(Point3& p_){
 | 
			
		||||
  void setP(const Point3& p_){
 | 
			
		||||
    p = p_;
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -243,13 +243,10 @@ struct SfmTrack {
 | 
			
		|||
  Point3 point3() const {
 | 
			
		||||
    return p;
 | 
			
		||||
  }
 | 
			
		||||
  void add_measurement(pair<size_t, gtsam::Point2>& m) const{
 | 
			
		||||
  void add_measurement(const pair<size_t, gtsam::Point2>& m) {
 | 
			
		||||
    measurements.push_back(m);
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  SfmMeasurements& measurements() {
 | 
			
		||||
    return measurements;
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
};
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -278,11 +275,11 @@ struct SfmData {
 | 
			
		|||
    return tracks[idx];
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  void add_track(SfmTrack& t) const {
 | 
			
		||||
  void add_track(const SfmTrack& t)  {
 | 
			
		||||
    tracks.push_back(t);
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  void add_camera(SfmCamera& cam) const{
 | 
			
		||||
  void add_camera(const SfmCamera& cam){
 | 
			
		||||
    cameras.push_back(cam);
 | 
			
		||||
  }
 | 
			
		||||
};
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -10,5 +10,5 @@ PYBIND11_MAKE_OPAQUE(std::vector<gtsam::Pose3>);
 | 
			
		|||
PYBIND11_MAKE_OPAQUE(std::vector<boost::shared_ptr<gtsam::BetweenFactor<gtsam::Pose3> > >);
 | 
			
		||||
PYBIND11_MAKE_OPAQUE(std::vector<boost::shared_ptr<gtsam::BetweenFactor<gtsam::Pose2> > >);
 | 
			
		||||
PYBIND11_MAKE_OPAQUE(std::vector<gtsam::IndexPair>);
 | 
			
		||||
PYBIND11_MAKE_OPAQUE(std::vector<gtsam::SfmMeasurement>);
 | 
			
		||||
PYBIND11_MAKE_OPAQUE(std::vector<gtsam::SiftIndex>);
 | 
			
		||||
//PYBIND11_MAKE_OPAQUE(std::vector<gtsam::SfmMeasurement>);
 | 
			
		||||
//PYBIND11_MAKE_OPAQUE(std::vector<gtsam::SiftIndex>);
 | 
			
		||||
| 
						 | 
				
			
			@ -13,5 +13,5 @@ py::bind_vector<std::vector<gtsam::BinaryMeasurement<gtsam::Unit3> > >(m_, "Bina
 | 
			
		|||
py::bind_map<gtsam::IndexPairSetMap>(m_, "IndexPairSetMap");
 | 
			
		||||
py::bind_vector<gtsam::IndexPairVector>(m_, "IndexPairVector");
 | 
			
		||||
py::bind_map<gtsam::KeyPairDoubleMap>(m_, "KeyPairDoubleMap");
 | 
			
		||||
py::bind_vector<std::vector<gtsam::SfmMeasurement> >(m_, "Measurement");
 | 
			
		||||
py::bind_vector<std::vector<gtsam::SiftIndex> >(m_, "SiftIndexVector");
 | 
			
		||||
//py::bind_vector<std::vector<gtsam::SfmMeasurement> >(m_, "Measurement");
 | 
			
		||||
//py::bind_vector<std::vector<gtsam::SiftIndex> >(m_, "SiftIndexVector");
 | 
			
		||||
		Loading…
	
		Reference in New Issue