| 
									
										
										
										
											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>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-11-20 10:30:44 +08:00
										 |  |  | #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | using namespace boost::python; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | void exportLevenbergMarquardtOptimizer(){ | 
					
						
							| 
									
										
										
										
											2016-01-25 16:58:08 +08:00
										 |  |  |   class_<LevenbergMarquardtParams>("LevenbergMarquardtParams", init<>()) | 
					
						
							|  |  |  |   .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) | 
					
						
							|  |  |  |   ; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-11-20 10:30:44 +08:00
										 |  |  |   class_<LevenbergMarquardtOptimizer>("LevenbergMarquardtOptimizer", | 
					
						
							|  |  |  |     init<const NonlinearFactorGraph&, const Values&, const LevenbergMarquardtParams&>()) | 
					
						
							|  |  |  |   .def("optimize", &LevenbergMarquardtOptimizer::optimize, return_value_policy<copy_const_reference>()) | 
					
						
							|  |  |  |   ; | 
					
						
							| 
									
										
										
										
											2016-01-25 16:58:08 +08:00
										 |  |  | } |