| 
									
										
										
										
											2013-11-20 10:30:44 +08:00
										 |  |  | #include <boost/python.hpp>
 | 
					
						
							| 
									
										
										
										
											2015-11-21 04:40:40 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | #define NO_IMPORT_ARRAY
 | 
					
						
							|  |  |  | #include <numpy_eigen/NumpyEigenConverter.hpp>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-02-25 03:01:19 +08:00
										 |  |  | #include <gtsam/nonlinear/GaussNewtonOptimizer.h>
 | 
					
						
							| 
									
										
										
										
											2013-11-20 10:30:44 +08:00
										 |  |  | #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
 | 
					
						
							| 
									
										
										
										
											2016-02-25 03:01:19 +08:00
										 |  |  | #include <gtsam/nonlinear/Marginals.h>
 | 
					
						
							| 
									
										
										
										
											2013-11-20 10:30:44 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace boost::python; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-02-25 03:01:19 +08:00
										 |  |  | void exportLevenbergMarquardtOptimizer() { | 
					
						
							|  |  |  |   class_<GaussNewtonParams>("GaussNewtonParams", init<>()) | 
					
						
							|  |  |  |       .def_readwrite("maxIterations", &GaussNewtonParams::maxIterations) | 
					
						
							|  |  |  |       .def_readwrite("relativeErrorTol", &GaussNewtonParams::relativeErrorTol); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-06-19 14:13:59 +08:00
										 |  |  |   class_<GaussNewtonOptimizer, boost::noncopyable>( | 
					
						
							| 
									
										
										
										
											2016-02-25 03:01:19 +08:00
										 |  |  |       "GaussNewtonOptimizer", | 
					
						
							|  |  |  |       init<const NonlinearFactorGraph&, const Values&, const GaussNewtonParams&>()) | 
					
						
							|  |  |  |       .def("optimize", &GaussNewtonOptimizer::optimize, | 
					
						
							|  |  |  |            return_value_policy<copy_const_reference>()); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-01-25 16:58:08 +08:00
										 |  |  |   class_<LevenbergMarquardtParams>("LevenbergMarquardtParams", init<>()) | 
					
						
							| 
									
										
										
										
											2016-02-25 03:01:19 +08:00
										 |  |  |       .def("setDiagonalDamping", &LevenbergMarquardtParams::setDiagonalDamping) | 
					
						
							|  |  |  |       .def("setlambdaFactor", &LevenbergMarquardtParams::setlambdaFactor) | 
					
						
							|  |  |  |       .def("setlambdaInitial", &LevenbergMarquardtParams::setlambdaInitial) | 
					
						
							|  |  |  |       .def("setlambdaLowerBound", &LevenbergMarquardtParams::setlambdaLowerBound) | 
					
						
							|  |  |  |       .def("setlambdaUpperBound", &LevenbergMarquardtParams::setlambdaUpperBound) | 
					
						
							|  |  |  |       .def("setLogFile", &LevenbergMarquardtParams::setLogFile) | 
					
						
							|  |  |  |       .def("setUseFixedLambdaFactor", &LevenbergMarquardtParams::setUseFixedLambdaFactor) | 
					
						
							|  |  |  |       .def("setVerbosityLM", &LevenbergMarquardtParams::setVerbosityLM); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-06-19 14:13:59 +08:00
										 |  |  |   class_<LevenbergMarquardtOptimizer, boost::noncopyable>( | 
					
						
							| 
									
										
										
										
											2016-02-25 03:01:19 +08:00
										 |  |  |       "LevenbergMarquardtOptimizer", | 
					
						
							|  |  |  |       init<const NonlinearFactorGraph&, const Values&, const LevenbergMarquardtParams&>()) | 
					
						
							|  |  |  |       .def("optimize", &LevenbergMarquardtOptimizer::optimize, | 
					
						
							|  |  |  |            return_value_policy<copy_const_reference>()); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   class_<Marginals>("Marginals", init<const NonlinearFactorGraph&, const Values&>()) | 
					
						
							|  |  |  |       .def("marginalCovariance", &Marginals::marginalCovariance); | 
					
						
							| 
									
										
										
										
											2016-01-25 16:58:08 +08:00
										 |  |  | } |