Correct the binding for BinaryMeasurement
							parent
							
								
									21b8365d7b
								
							
						
					
					
						commit
						28b216b72f
					
				|  | @ -223,6 +223,7 @@ parse3DFactors(const std::string &filename, | |||
|                size_t maxIndex = 0); | ||||
| 
 | ||||
| using BinaryMeasurementsUnit3 = std::vector<BinaryMeasurement<Unit3>>; | ||||
| using BinaryMeasurementsRot3 = std::vector<BinaryMeasurement<Rot3>>; | ||||
| 
 | ||||
| #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 | ||||
| inline boost::optional<IndexedPose> GTSAM_DEPRECATED | ||||
|  |  | |||
|  | @ -48,6 +48,7 @@ set(ignore | |||
|     gtsam::Rot3Vector | ||||
|     gtsam::KeyVector | ||||
|     gtsam::BinaryMeasurementsUnit3 | ||||
|     gtsam::BinaryMeasurementsRot3 | ||||
|     gtsam::DiscreteKey | ||||
|     gtsam::KeyPairDoubleMap) | ||||
| 
 | ||||
|  | @ -137,6 +138,7 @@ if(GTSAM_UNSTABLE_BUILD_PYTHON) | |||
|             gtsam::KeyVector | ||||
|             gtsam::FixedLagSmootherKeyTimestampMapValue | ||||
|             gtsam::BinaryMeasurementsUnit3 | ||||
|             gtsam::BinaryMeasurementsRot3 | ||||
|             gtsam::CameraSetCal3_S2 | ||||
|             gtsam::CameraSetCal3Bundler | ||||
|             gtsam::CameraSetCal3Unified | ||||
|  |  | |||
|  | @ -18,4 +18,8 @@ PYBIND11_MAKE_OPAQUE( | |||
|     std::vector<gtsam::SfmTrack>); | ||||
| 
 | ||||
| PYBIND11_MAKE_OPAQUE( | ||||
|     std::vector<gtsam::SfmCamera>); | ||||
|     std::vector<gtsam::SfmCamera>); | ||||
| PYBIND11_MAKE_OPAQUE( | ||||
|     std::vector<gtsam::BinaryMeasurement<gtsam::Unit3>>); | ||||
| PYBIND11_MAKE_OPAQUE( | ||||
|     std::vector<gtsam::BinaryMeasurement<gtsam::Rot3>>); | ||||
|  |  | |||
|  | @ -13,6 +13,8 @@ | |||
| 
 | ||||
| py::bind_vector<std::vector<gtsam::BinaryMeasurement<gtsam::Unit3> > >( | ||||
|     m_, "BinaryMeasurementsUnit3"); | ||||
| py::bind_vector<std::vector<gtsam::BinaryMeasurement<gtsam::Rot3> > >( | ||||
|     m_, "BinaryMeasurementsRot3"); | ||||
| py::bind_map<gtsam::KeyPairDoubleMap>(m_, "KeyPairDoubleMap"); | ||||
| 
 | ||||
| py::bind_vector< | ||||
|  |  | |||
		Loading…
	
		Reference in New Issue