uncomment calibration applications
							parent
							
								
									0b81b763a2
								
							
						
					
					
						commit
						cb3a766b30
					
				|  | @ -31,9 +31,8 @@ namespace gtsam { | |||
|   /// Also needed as forward declarations in the wrapper.
 | ||||
|   using PinholeCameraCal3_S2 = gtsam::PinholeCamera<gtsam::Cal3_S2>; | ||||
|   using PinholeCameraCal3Bundler = gtsam::PinholeCamera<gtsam::Cal3Bundler>; | ||||
|   //TODO Need to fix issue 621 for this to work with wrapper
 | ||||
|   // using PinholeCameraCal3DS2 = gtsam::PinholeCamera<gtsam::Cal3DS2>;
 | ||||
|   // using PinholeCameraCal3Unified = gtsam::PinholeCamera<gtsam::Cal3Unified>;
 | ||||
|   using PinholeCameraCal3DS2 = gtsam::PinholeCamera<gtsam::Cal3DS2>; | ||||
|   using PinholeCameraCal3Unified = gtsam::PinholeCamera<gtsam::Cal3Unified>; | ||||
| 
 | ||||
| #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41 | ||||
| /**
 | ||||
|  |  | |||
|  | @ -881,7 +881,7 @@ virtual class Cal3DS2_Base { | |||
| 
 | ||||
|   // Action on Point2 | ||||
|   gtsam::Point2 uncalibrate(const gtsam::Point2& p) const; | ||||
|   gtsam::Point2 calibrate(const gtsam::Point2& p, double tol) const; | ||||
|   gtsam::Point2 calibrate(const gtsam::Point2& p) const; | ||||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
|  | @ -1064,9 +1064,8 @@ class PinholeCamera { | |||
| // Some typedefs for common camera types | ||||
| // PinholeCameraCal3_S2 is the same as SimpleCamera above | ||||
| typedef gtsam::PinholeCamera<gtsam::Cal3_S2> PinholeCameraCal3_S2; | ||||
| //TODO (Issue 621) due to lack of jacobians of Cal3DS2_Base::calibrate, PinholeCamera does not apply to Cal3DS2/Unified | ||||
| //typedef gtsam::PinholeCamera<gtsam::Cal3DS2> PinholeCameraCal3DS2; | ||||
| //typedef gtsam::PinholeCamera<gtsam::Cal3Unified> PinholeCameraCal3Unified; | ||||
| typedef gtsam::PinholeCamera<gtsam::Cal3DS2> PinholeCameraCal3DS2; | ||||
| typedef gtsam::PinholeCamera<gtsam::Cal3Unified> PinholeCameraCal3Unified; | ||||
| typedef gtsam::PinholeCamera<gtsam::Cal3Bundler> PinholeCameraCal3Bundler; | ||||
| 
 | ||||
| #include <gtsam/geometry/StereoCamera.h> | ||||
|  | @ -2634,8 +2633,7 @@ virtual class GeneralSFMFactor : gtsam::NoiseModelFactor { | |||
|   gtsam::Point2 measured() const; | ||||
| }; | ||||
| typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3_S2, gtsam::Point3> GeneralSFMFactorCal3_S2; | ||||
| //TODO (Issue 621) due to lack of jacobians of Cal3DS2_Base::calibrate, GeneralSFMFactor does not apply to Cal3DS2 | ||||
| //typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3DS2, gtsam::Point3> GeneralSFMFactorCal3DS2; | ||||
| typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3DS2, gtsam::Point3> GeneralSFMFactorCal3DS2; | ||||
| typedef gtsam::GeneralSFMFactor<gtsam::PinholeCamera<gtsam::Cal3Bundler>, gtsam::Point3> GeneralSFMFactorCal3Bundler; | ||||
| 
 | ||||
| template<CALIBRATION = {gtsam::Cal3_S2}> | ||||
|  |  | |||
|  | @ -86,8 +86,7 @@ typedef GenericProjectionFactor<Pose3, Point3, Cal3_S2> GenericProjectionFactorC | |||
| typedef GenericProjectionFactor<Pose3, Point3, Cal3DS2> GenericProjectionFactorCal3DS2; | ||||
| 
 | ||||
| typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3_S2, gtsam::Point3> GeneralSFMFactorCal3_S2; | ||||
| //TODO fix issue 621
 | ||||
| //typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3DS2, gtsam::Point3> GeneralSFMFactorCal3DS2;
 | ||||
| typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3DS2, gtsam::Point3> GeneralSFMFactorCal3DS2; | ||||
| 
 | ||||
| typedef gtsam::GeneralSFMFactor2<gtsam::Cal3_S2> GeneralSFMFactor2Cal3_S2; | ||||
| 
 | ||||
|  | @ -184,8 +183,7 @@ BOOST_CLASS_EXPORT_GUID(GenericProjectionFactorCal3_S2, "gtsam::GenericProjectio | |||
| BOOST_CLASS_EXPORT_GUID(GenericProjectionFactorCal3DS2, "gtsam::GenericProjectionFactorCal3DS2"); | ||||
| 
 | ||||
| BOOST_CLASS_EXPORT_GUID(GeneralSFMFactorCal3_S2, "gtsam::GeneralSFMFactorCal3_S2"); | ||||
| //TODO Fix issue 621
 | ||||
| //BOOST_CLASS_EXPORT_GUID(GeneralSFMFactorCal3DS2, "gtsam::GeneralSFMFactorCal3DS2");
 | ||||
| BOOST_CLASS_EXPORT_GUID(GeneralSFMFactorCal3DS2, "gtsam::GeneralSFMFactorCal3DS2"); | ||||
| 
 | ||||
| BOOST_CLASS_EXPORT_GUID(GeneralSFMFactor2Cal3_S2, "gtsam::GeneralSFMFactor2Cal3_S2"); | ||||
| 
 | ||||
|  |  | |||
|  | @ -100,8 +100,7 @@ typedef GenericProjectionFactor<Pose3, Point3, Cal3_S2> GenericProjectionFactorC | |||
| typedef GenericProjectionFactor<Pose3, Point3, Cal3DS2> GenericProjectionFactorCal3DS2; | ||||
| 
 | ||||
| typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3_S2, gtsam::Point3> GeneralSFMFactorCal3_S2; | ||||
| //TODO Fix issue 621 for this to work
 | ||||
| //typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3DS2, gtsam::Point3> GeneralSFMFactorCal3DS2;
 | ||||
| typedef gtsam::GeneralSFMFactor<gtsam::PinholeCameraCal3DS2, gtsam::Point3> GeneralSFMFactorCal3DS2; | ||||
| 
 | ||||
| typedef gtsam::GeneralSFMFactor2<gtsam::Cal3_S2> GeneralSFMFactor2Cal3_S2; | ||||
| 
 | ||||
|  | @ -198,8 +197,7 @@ BOOST_CLASS_EXPORT_GUID(GenericProjectionFactorCal3_S2, "gtsam::GenericProjectio | |||
| BOOST_CLASS_EXPORT_GUID(GenericProjectionFactorCal3DS2, "gtsam::GenericProjectionFactorCal3DS2"); | ||||
| 
 | ||||
| BOOST_CLASS_EXPORT_GUID(GeneralSFMFactorCal3_S2, "gtsam::GeneralSFMFactorCal3_S2"); | ||||
| //TODO fix issue 621
 | ||||
| //BOOST_CLASS_EXPORT_GUID(GeneralSFMFactorCal3DS2, "gtsam::GeneralSFMFactorCal3DS2");
 | ||||
| BOOST_CLASS_EXPORT_GUID(GeneralSFMFactorCal3DS2, "gtsam::GeneralSFMFactorCal3DS2"); | ||||
| 
 | ||||
| BOOST_CLASS_EXPORT_GUID(GeneralSFMFactor2Cal3_S2, "gtsam::GeneralSFMFactor2Cal3_S2"); | ||||
| 
 | ||||
|  |  | |||
		Loading…
	
		Reference in New Issue