wrap vector of NamedSfmMeasurement
							parent
							
								
									fa17c50910
								
							
						
					
					
						commit
						96aaff4bc6
					
				| 
						 | 
					@ -95,7 +95,7 @@ class SfmTrack2d {
 | 
				
			||||||
};
 | 
					};
 | 
				
			||||||
 | 
					
 | 
				
			||||||
using SfmTrack2dVector = std::vector<gtsam::SfmTrack2d>;
 | 
					using SfmTrack2dVector = std::vector<gtsam::SfmTrack2d>;
 | 
				
			||||||
 | 
					using NamedSfmMeasurementVector = std::vector<NamedSfmMeasurement>;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					
 | 
				
			||||||
/**
 | 
					/**
 | 
				
			||||||
| 
						 | 
					
 | 
				
			||||||
| 
						 | 
					@ -42,6 +42,16 @@ class NamedSfmMeasurement
 | 
				
			||||||
  NamedSfmMeasurement(size_t i, gtsam::Point2 uv);
 | 
					  NamedSfmMeasurement(size_t i, gtsam::Point2 uv);
 | 
				
			||||||
};
 | 
					};
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					class NamedSfmMeasurementVector {
 | 
				
			||||||
 | 
					  NamedSfmMeasurementVector();
 | 
				
			||||||
 | 
					  NamedSfmMeasurementVector(const gtsam::NamedSfmMeasurementVector& other);
 | 
				
			||||||
 | 
					  void push_back(const gtsam::NamedSfmMeasurement& measurement);
 | 
				
			||||||
 | 
					  size_t size() const;
 | 
				
			||||||
 | 
					  bool empty() const;
 | 
				
			||||||
 | 
					  void clear();
 | 
				
			||||||
 | 
					  gtsam::NamedSfmMeasurement at(const size_t& index) const;
 | 
				
			||||||
 | 
					};
 | 
				
			||||||
 | 
					
 | 
				
			||||||
class SfmTrack2d
 | 
					class SfmTrack2d
 | 
				
			||||||
{
 | 
					{
 | 
				
			||||||
  void addMeasurement(const gtsam::NamedSfmMeasurement &m);
 | 
					  void addMeasurement(const gtsam::NamedSfmMeasurement &m);
 | 
				
			||||||
| 
						 | 
					@ -52,7 +62,7 @@ class SfmTrack2d
 | 
				
			||||||
class SfmTrack2dVector {
 | 
					class SfmTrack2dVector {
 | 
				
			||||||
  SfmTrack2dVector();
 | 
					  SfmTrack2dVector();
 | 
				
			||||||
  SfmTrack2dVector(const gtsam::SfmTrack2dVector& other);
 | 
					  SfmTrack2dVector(const gtsam::SfmTrack2dVector& other);
 | 
				
			||||||
  void push_back(const gtsam::SfmTrack2d& keypoints);
 | 
					  void push_back(const gtsam::SfmTrack2d& track);
 | 
				
			||||||
  size_t size() const;
 | 
					  size_t size() const;
 | 
				
			||||||
  bool empty() const;
 | 
					  bool empty() const;
 | 
				
			||||||
  void clear();
 | 
					  void clear();
 | 
				
			||||||
| 
						 | 
					
 | 
				
			||||||
| 
						 | 
					@ -54,7 +54,8 @@ set(ignore
 | 
				
			||||||
    gtsam::KeyPairDoubleMap
 | 
					    gtsam::KeyPairDoubleMap
 | 
				
			||||||
    gtsam::MatchIndicesMap
 | 
					    gtsam::MatchIndicesMap
 | 
				
			||||||
    gtsam::KeypointsList
 | 
					    gtsam::KeypointsList
 | 
				
			||||||
    gtsam::SfmTrack2dVector)
 | 
					    gtsam::SfmTrack2dVector
 | 
				
			||||||
 | 
					    gtsam::NamedSfmMeasurementVector)
 | 
				
			||||||
 | 
					
 | 
				
			||||||
set(interface_headers
 | 
					set(interface_headers
 | 
				
			||||||
    ${PROJECT_SOURCE_DIR}/gtsam/gtsam.i
 | 
					    ${PROJECT_SOURCE_DIR}/gtsam/gtsam.i
 | 
				
			||||||
| 
						 | 
					@ -154,7 +155,8 @@ if(GTSAM_UNSTABLE_BUILD_PYTHON)
 | 
				
			||||||
            gtsam::KeyPairDoubleMap
 | 
					            gtsam::KeyPairDoubleMap
 | 
				
			||||||
            gtsam::MatchIndicesMap
 | 
					            gtsam::MatchIndicesMap
 | 
				
			||||||
            gtsam::KeypointsList
 | 
					            gtsam::KeypointsList
 | 
				
			||||||
            gtsam::SfmTrack2dVector)
 | 
					            gtsam::SfmTrack2dVector
 | 
				
			||||||
 | 
					            gtsam::NamedSfmMeasurementVector)
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					
 | 
				
			||||||
    pybind_wrap(${GTSAM_PYTHON_UNSTABLE_TARGET} # target
 | 
					    pybind_wrap(${GTSAM_PYTHON_UNSTABLE_TARGET} # target
 | 
				
			||||||
| 
						 | 
					
 | 
				
			||||||
| 
						 | 
					@ -30,3 +30,6 @@ PYBIND11_MAKE_OPAQUE(
 | 
				
			||||||
//     std::vector<gtsam::SfmTrack2d>);
 | 
					//     std::vector<gtsam::SfmTrack2d>);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
PYBIND11_MAKE_OPAQUE(gtsam::MatchIndicesMap);
 | 
					PYBIND11_MAKE_OPAQUE(gtsam::MatchIndicesMap);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					PYBIND11_MAKE_OPAQUE(
 | 
				
			||||||
 | 
					    std::vector<gtsam::NamedSfmMeasurement>);
 | 
				
			||||||
| 
						 | 
					@ -40,3 +40,7 @@ py::bind_vector<
 | 
				
			||||||
py::bind_vector<
 | 
					py::bind_vector<
 | 
				
			||||||
    std::vector<gtsam::SfmTrack2d> >(
 | 
					    std::vector<gtsam::SfmTrack2d> >(
 | 
				
			||||||
    m_, "SfmTrack2dVector");
 | 
					    m_, "SfmTrack2dVector");
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					py::bind_vector<
 | 
				
			||||||
 | 
					    std::vector<gtsam::NamedSfmMeasurement> >(
 | 
				
			||||||
 | 
					    m_, "NamedSfmMeasurementVector");
 | 
				
			||||||
| 
						 | 
					
 | 
				
			||||||
		Loading…
	
		Reference in New Issue