Merge branch 'develop' into feature/matlab-wrap
						commit
						99f351da4c
					
				|  | @ -6,5 +6,11 @@ configure_file( | |||
|   "${CMAKE_CURRENT_BINARY_DIR}/cmake_uninstall.cmake" | ||||
|   IMMEDIATE @ONLY) | ||||
| 
 | ||||
| add_custom_target(uninstall | ||||
|   "${CMAKE_COMMAND}" -P "${CMAKE_CURRENT_BINARY_DIR}/cmake_uninstall.cmake") | ||||
| if (NOT TARGET uninstall) # avoid duplicating this target | ||||
|   add_custom_target(uninstall | ||||
|     "${CMAKE_COMMAND}" -P "${CMAKE_CURRENT_BINARY_DIR}/cmake_uninstall.cmake") | ||||
| else() | ||||
|     add_custom_target(uninstall_gtsam | ||||
|       "${CMAKE_COMMAND}" -P "${CMAKE_CURRENT_BINARY_DIR}/cmake_uninstall.cmake") | ||||
|     add_dependencies(uninstall uninstall_gtsam) | ||||
| endif() | ||||
|  |  | |||
							
								
								
									
										100
									
								
								gtsam/gtsam.i
								
								
								
								
							
							
						
						
									
										100
									
								
								gtsam/gtsam.i
								
								
								
								
							|  | @ -105,6 +105,9 @@ | |||
|  *          virtual class MyFactor : gtsam::NoiseModelFactor {...}; | ||||
|  *    - *DO NOT* re-define overriden function already declared in the external (forward-declared) base class | ||||
|  *        - This will cause an ambiguity problem in Pybind header file | ||||
|  *   Pickle support in Python: | ||||
|  *    - Add "void pickle()" to a class to enable pickling via gtwrap. In the current implementation, "void serialize()" | ||||
|  *      and a public constructor with no-arguments in needed for successful build. | ||||
|  */ | ||||
| 
 | ||||
| /** | ||||
|  | @ -144,6 +147,9 @@ class KeyList { | |||
|   void remove(size_t key); | ||||
| 
 | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| }; | ||||
| 
 | ||||
| // Actually a FastSet<Key> | ||||
|  | @ -169,6 +175,9 @@ class KeySet { | |||
|   bool count(size_t key) const; // returns true if value exists | ||||
| 
 | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| }; | ||||
| 
 | ||||
| // Actually a vector<Key> | ||||
|  | @ -190,6 +199,9 @@ class KeyVector { | |||
|   void push_back(size_t key) const; | ||||
| 
 | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| }; | ||||
| 
 | ||||
| // Actually a FastMap<Key,int> | ||||
|  | @ -361,6 +373,9 @@ class Point2 { | |||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| }; | ||||
| 
 | ||||
| // std::vector<gtsam::Point2> | ||||
|  | @ -422,6 +437,9 @@ class StereoPoint2 { | |||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| }; | ||||
| 
 | ||||
| #include <gtsam/geometry/Point3.h> | ||||
|  | @ -446,6 +464,9 @@ class Point3 { | |||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| }; | ||||
| 
 | ||||
| #include <gtsam/geometry/Rot2.h> | ||||
|  | @ -491,6 +512,9 @@ class Rot2 { | |||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| }; | ||||
| 
 | ||||
| #include <gtsam/geometry/SO3.h> | ||||
|  | @ -653,6 +677,9 @@ class Rot3 { | |||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| }; | ||||
| 
 | ||||
| #include <gtsam/geometry/Pose2.h> | ||||
|  | @ -708,6 +735,9 @@ class Pose2 { | |||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| }; | ||||
| 
 | ||||
| #include <gtsam/geometry/Pose3.h> | ||||
|  | @ -764,6 +794,9 @@ class Pose3 { | |||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| }; | ||||
| 
 | ||||
| // std::vector<gtsam::Pose3> | ||||
|  | @ -797,6 +830,15 @@ class Unit3 { | |||
|   size_t dim() const; | ||||
|   gtsam::Unit3 retract(Vector v) const; | ||||
|   Vector localCoordinates(const gtsam::Unit3& s) const; | ||||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| 
 | ||||
|   // enabling function to compare objects | ||||
|   bool equals(const gtsam::Unit3& expected, double tol) const; | ||||
| }; | ||||
| 
 | ||||
| #include <gtsam/geometry/EssentialMatrix.h> | ||||
|  | @ -856,6 +898,9 @@ class Cal3_S2 { | |||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| }; | ||||
| 
 | ||||
| #include <gtsam/geometry/Cal3DS2_Base.h> | ||||
|  | @ -884,6 +929,9 @@ virtual class Cal3DS2_Base { | |||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| }; | ||||
| 
 | ||||
| #include <gtsam/geometry/Cal3DS2.h> | ||||
|  | @ -905,6 +953,9 @@ virtual class Cal3DS2 : gtsam::Cal3DS2_Base { | |||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| }; | ||||
| 
 | ||||
| #include <gtsam/geometry/Cal3Unified.h> | ||||
|  | @ -931,6 +982,9 @@ virtual class Cal3Unified : gtsam::Cal3DS2_Base { | |||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| }; | ||||
| 
 | ||||
| #include <gtsam/geometry/Cal3_S2Stereo.h> | ||||
|  | @ -988,6 +1042,9 @@ class Cal3Bundler { | |||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| }; | ||||
| 
 | ||||
| #include <gtsam/geometry/CalibratedCamera.h> | ||||
|  | @ -1018,6 +1075,9 @@ class CalibratedCamera { | |||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| }; | ||||
| 
 | ||||
| #include <gtsam/geometry/PinholeCamera.h> | ||||
|  | @ -1056,6 +1116,9 @@ class PinholeCamera { | |||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| }; | ||||
| 
 | ||||
| // Forward declaration of PinholeCameraCalX is defined here. | ||||
|  | @ -1103,6 +1166,9 @@ class StereoCamera { | |||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| }; | ||||
| 
 | ||||
| #include <gtsam/geometry/triangulation.h> | ||||
|  | @ -1557,6 +1623,9 @@ class VectorValues { | |||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| }; | ||||
| 
 | ||||
| #include <gtsam/linear/GaussianFactor.h> | ||||
|  | @ -1618,6 +1687,9 @@ virtual class JacobianFactor : gtsam::GaussianFactor { | |||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| }; | ||||
| 
 | ||||
| #include <gtsam/linear/HessianFactor.h> | ||||
|  | @ -1649,6 +1721,9 @@ virtual class HessianFactor : gtsam::GaussianFactor { | |||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| }; | ||||
| 
 | ||||
| #include <gtsam/linear/GaussianFactorGraph.h> | ||||
|  | @ -1728,6 +1803,9 @@ class GaussianFactorGraph { | |||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| }; | ||||
| 
 | ||||
| #include <gtsam/linear/GaussianConditional.h> | ||||
|  | @ -2035,6 +2113,9 @@ class Ordering { | |||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| }; | ||||
| 
 | ||||
| #include <gtsam/nonlinear/NonlinearFactorGraph.h> | ||||
|  | @ -2073,6 +2154,10 @@ class NonlinearFactorGraph { | |||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| 
 | ||||
|   void saveGraph(const string& s) const; | ||||
| }; | ||||
| 
 | ||||
|  | @ -2130,6 +2215,9 @@ class Values { | |||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| 
 | ||||
|   // New in 4.0, we have to specialize every insert/update/at to generate wrappers | ||||
|   // Instead of the old: | ||||
|   // void insert(size_t j, const gtsam::Value& value); | ||||
|  | @ -2529,6 +2617,9 @@ virtual class PriorFactor : gtsam::NoiseModelFactor { | |||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| }; | ||||
| 
 | ||||
| 
 | ||||
|  | @ -2540,6 +2631,9 @@ virtual class BetweenFactor : gtsam::NoiseModelFactor { | |||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| }; | ||||
| 
 | ||||
| #include <gtsam/nonlinear/NonlinearEquality.h> | ||||
|  | @ -2776,6 +2870,9 @@ class SfmTrack { | |||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| 
 | ||||
|   // enabling function to compare objects | ||||
|   bool equals(const gtsam::SfmTrack& expected, double tol) const; | ||||
| }; | ||||
|  | @ -2792,6 +2889,9 @@ class SfmData { | |||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
| 
 | ||||
|   // enable pickling in python | ||||
|   void pickle() const; | ||||
| 
 | ||||
|   // enabling function to compare objects | ||||
|   bool equals(const gtsam::SfmData& expected, double tol) const; | ||||
| }; | ||||
|  |  | |||
|  | @ -0,0 +1,46 @@ | |||
| """ | ||||
| GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, | ||||
| Atlanta, Georgia 30332-0415 | ||||
| All Rights Reserved | ||||
| 
 | ||||
| See LICENSE for the license information | ||||
| 
 | ||||
| Unit tests to check pickling. | ||||
| 
 | ||||
| Author: Ayush Baid | ||||
| """ | ||||
| from gtsam import Cal3Bundler, PinholeCameraCal3Bundler, Point2, Point3, Pose3, Rot3, SfmTrack, Unit3  | ||||
| 
 | ||||
| from gtsam.utils.test_case import GtsamTestCase | ||||
| 
 | ||||
| class TestPickle(GtsamTestCase): | ||||
|     """Tests pickling on some of the classes.""" | ||||
| 
 | ||||
|     def test_cal3Bundler_roundtrip(self): | ||||
|         obj = Cal3Bundler(fx=100, k1=0.1, k2=0.2, u0=100, v0=70) | ||||
|         self.assertEqualityOnPickleRoundtrip(obj) | ||||
|      | ||||
|     def test_pinholeCameraCal3Bundler_roundtrip(self): | ||||
|         obj = PinholeCameraCal3Bundler( | ||||
|             Pose3(Rot3.RzRyRx(0, 0.1, -0.05), Point3(1, 1, 0)), | ||||
|             Cal3Bundler(fx=100, k1=0.1, k2=0.2, u0=100, v0=70), | ||||
|         ) | ||||
|         self.assertEqualityOnPickleRoundtrip(obj) | ||||
|      | ||||
|     def test_rot3_roundtrip(self): | ||||
|         obj = Rot3.RzRyRx(0, 0.05, 0.1) | ||||
|         self.assertEqualityOnPickleRoundtrip(obj) | ||||
| 
 | ||||
|     def test_pose3_roundtrip(self): | ||||
|         obj = Pose3(Rot3.Ypr(0.0, 1.0, 0.0), Point3(1, 1, 0)) | ||||
|         self.assertEqualityOnPickleRoundtrip(obj) | ||||
| 
 | ||||
|     def test_sfmTrack_roundtrip(self): | ||||
|         obj = SfmTrack(Point3(1, 1, 0)) | ||||
|         obj.add_measurement(0, Point2(-1, 5)) | ||||
|         obj.add_measurement(1, Point2(6, 2)) | ||||
|         self.assertEqualityOnPickleRoundtrip(obj) | ||||
| 
 | ||||
|     def test_unit3_roundtrip(self): | ||||
|         obj = Unit3(Point3(1, 1, 0)) | ||||
|         self.assertEqualityOnPickleRoundtrip(obj) | ||||
|  | @ -8,6 +8,7 @@ See LICENSE for the license information | |||
| TestCase class with GTSAM assert utils. | ||||
| Author: Frank Dellaert | ||||
| """ | ||||
| import pickle | ||||
| import unittest | ||||
| 
 | ||||
| 
 | ||||
|  | @ -29,3 +30,14 @@ class GtsamTestCase(unittest.TestCase): | |||
|         if not equal: | ||||
|             raise self.failureException( | ||||
|                 "Values are not equal:\n{}!={}".format(actual, expected)) | ||||
| 
 | ||||
|     def assertEqualityOnPickleRoundtrip(self, obj: object, tol=1e-9) -> None: | ||||
|         """ Performs a round-trip using pickle and asserts equality. | ||||
| 
 | ||||
|             Usage: | ||||
|                 self.assertEqualityOnPickleRoundtrip(obj) | ||||
|             Keyword Arguments: | ||||
|                 tol {float} -- tolerance passed to 'equals', default 1e-9 | ||||
|         """ | ||||
|         roundTripObj = pickle.loads(pickle.dumps(obj)) | ||||
|         self.gtsamAssertEquals(roundTripObj, obj) | ||||
|  |  | |||
		Loading…
	
		Reference in New Issue