| 
									
										
										
										
											2015-11-20 01:31:38 +08:00
										 |  |  | /* ----------------------------------------------------------------------------
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 |  |  |  * GTSAM Copyright 2010, Georgia Tech Research Corporation, | 
					
						
							| 
									
										
										
										
											2015-11-20 01:31:38 +08:00
										 |  |  |  * Atlanta, Georgia 30332-0415 | 
					
						
							|  |  |  |  * All Rights Reserved | 
					
						
							|  |  |  |  * Authors: Frank Dellaert, et al. (see THANKS for the full author list) | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * See LICENSE for the license information | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * @brief exports ISAM2 class to python | 
					
						
							|  |  |  |  * @author Ellon Paiva Mendes (LAAS-CNRS) | 
					
						
							|  |  |  |  **/ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <boost/python.hpp>
 | 
					
						
							| 
									
										
										
										
											2015-11-21 04:40:40 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | #define NO_IMPORT_ARRAY
 | 
					
						
							|  |  |  | #include <numpy_eigen/NumpyEigenConverter.hpp>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-11-20 01:31:38 +08:00
										 |  |  | #include "gtsam/nonlinear/ISAM2.h"
 | 
					
						
							| 
									
										
										
										
											2015-12-12 01:20:33 +08:00
										 |  |  | #include "gtsam/geometry/Pose3.h"
 | 
					
						
							| 
									
										
										
										
											2015-11-20 01:31:38 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace boost::python; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(update_overloads, ISAM2::update, 0, 7) | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | void exportISAM2(){ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // TODO(Ellon): Export all properties of ISAM2Params
 | 
					
						
							|  |  |  | class_<ISAM2Params>("ISAM2Params") | 
					
						
							| 
									
										
										
										
											2015-11-24 18:30:35 +08:00
										 |  |  |   .add_property("relinearize_skip", &ISAM2Params::getRelinearizeSkip, &ISAM2Params::setRelinearizeSkip) | 
					
						
							|  |  |  |   .add_property("enable_relinearization", &ISAM2Params::isEnableRelinearization, &ISAM2Params::setEnableRelinearization) | 
					
						
							|  |  |  |   .add_property("evaluate_non_linear_error", &ISAM2Params::isEvaluateNonlinearError, &ISAM2Params::setEvaluateNonlinearError) | 
					
						
							|  |  |  |   .add_property("factorization", &ISAM2Params::getFactorization, &ISAM2Params::setFactorization) | 
					
						
							|  |  |  |   .add_property("cache_linearized_factors", &ISAM2Params::isCacheLinearizedFactors, &ISAM2Params::setCacheLinearizedFactors) | 
					
						
							|  |  |  |   .add_property("enable_detailed_results", &ISAM2Params::isEnableDetailedResults, &ISAM2Params::setEnableDetailedResults) | 
					
						
							|  |  |  |   .add_property("enable_partial_linearization_check", &ISAM2Params::isEnablePartialRelinearizationCheck, &ISAM2Params::setEnablePartialRelinearizationCheck) | 
					
						
							|  |  |  |   // TODO(Ellon): Check if it works with FastMap; Implement properly if it doesn't.
 | 
					
						
							|  |  |  |   .add_property("relinearization_threshold", &ISAM2Params::getRelinearizeThreshold, &ISAM2Params::setRelinearizeThreshold) | 
					
						
							|  |  |  |   // TODO(Ellon): Wrap the following setters/getters:
 | 
					
						
							|  |  |  |   //     void 	setOptimizationParams (OptimizationParams optimizationParams)
 | 
					
						
							|  |  |  |   //     OptimizationParams 	getOptimizationParams () const
 | 
					
						
							|  |  |  |   //     void 	setKeyFormatter (KeyFormatter keyFormatter)
 | 
					
						
							|  |  |  |   //     KeyFormatter 	getKeyFormatter () const
 | 
					
						
							| 
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 |  |  |   //     GaussianFactorGraph::Eliminate 	getEliminationFunction () const
 | 
					
						
							| 
									
										
										
										
											2015-11-20 01:31:38 +08:00
										 |  |  | ; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // TODO(Ellon): Export useful methods/properties of ISAM2Result
 | 
					
						
							|  |  |  | class_<ISAM2Result>("ISAM2Result") | 
					
						
							|  |  |  | ; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // Function pointers for overloads in ISAM2
 | 
					
						
							|  |  |  | Values (ISAM2::*calculateEstimate_0)() const = &ISAM2::calculateEstimate; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | class_<ISAM2>("ISAM2") | 
					
						
							| 
									
										
										
										
											2015-11-24 06:22:18 +08:00
										 |  |  |   .def(init<const ISAM2Params &>()) | 
					
						
							| 
									
										
										
										
											2015-11-20 01:31:38 +08:00
										 |  |  |   // TODO(Ellon): wrap all optional values of update
 | 
					
						
							|  |  |  |   .def("update",&ISAM2::update, update_overloads()) | 
					
						
							|  |  |  |   .def("calculate_estimate", calculateEstimate_0) | 
					
						
							| 
									
										
										
										
											2015-12-12 01:20:33 +08:00
										 |  |  |   .def("calculate_pose3_estimate", &ISAM2::calculateEstimate<Pose3>, (arg("self"), arg("key")) ) | 
					
						
							|  |  |  |   .def("value_exists", &ISAM2::valueExists) | 
					
						
							| 
									
										
										
										
											2015-11-20 01:31:38 +08:00
										 |  |  | ; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | } |