| 
									
										
										
										
											2015-11-20 01:31:38 +08:00
										 |  |  | /* ----------------------------------------------------------------------------
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-01-28 17:32:20 +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 wraps BetweenFactor for several values to python | 
					
						
							| 
									
										
										
										
											2016-01-28 17:32:20 +08:00
										 |  |  |  * @author Andrew Melim | 
					
						
							| 
									
										
										
										
											2015-11-20 01:31:38 +08:00
										 |  |  |  * @author Ellon Paiva Mendes (LAAS-CNRS) | 
					
						
							|  |  |  |  **/ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-11-19 12:28:38 +08:00
										 |  |  | #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/slam/BetweenFactor.h"
 | 
					
						
							|  |  |  | #include "gtsam/geometry/Point2.h"
 | 
					
						
							|  |  |  | #include "gtsam/geometry/Rot2.h"
 | 
					
						
							|  |  |  | #include "gtsam/geometry/Pose2.h"
 | 
					
						
							|  |  |  | #include "gtsam/geometry/Point3.h"
 | 
					
						
							|  |  |  | #include "gtsam/geometry/Rot3.h"
 | 
					
						
							|  |  |  | #include "gtsam/geometry/Pose3.h"
 | 
					
						
							| 
									
										
										
										
											2013-11-19 12:28:38 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace boost::python; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-01-28 17:32:20 +08:00
										 |  |  | // template<class T>
 | 
					
						
							| 
									
										
										
										
											2015-11-20 01:31:38 +08:00
										 |  |  | // void exportBetweenFactor(const std::string& name){
 | 
					
						
							| 
									
										
										
										
											2016-01-28 17:32:20 +08:00
										 |  |  | //   class_<T>(name, init<>())
 | 
					
						
							|  |  |  | //   .def(init<Key, Key, T, SharedNoiseModel>())
 | 
					
						
							| 
									
										
										
										
											2015-11-20 01:31:38 +08:00
										 |  |  | //   ;
 | 
					
						
							|  |  |  | // }
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-01-28 17:32:20 +08:00
										 |  |  | #define BETWEENFACTOR(T) \
 | 
					
						
							|  |  |  |   class_< BetweenFactor<T>, bases<NonlinearFactor>, boost::shared_ptr< BetweenFactor<T> > >("BetweenFactor"#T) \ | 
					
						
							|  |  |  |   .def(init<Key,Key,T,noiseModel::Base::shared_ptr>()) \ | 
					
						
							|  |  |  |   .def("measured", &BetweenFactor<T>::measured, return_internal_reference<>()) \ | 
					
						
							| 
									
										
										
										
											2015-11-20 01:31:38 +08:00
										 |  |  | ; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | void exportBetweenFactors() | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  |   BETWEENFACTOR(Point2) | 
					
						
							|  |  |  |   BETWEENFACTOR(Rot2) | 
					
						
							|  |  |  |   BETWEENFACTOR(Pose2) | 
					
						
							|  |  |  |   BETWEENFACTOR(Point3) | 
					
						
							|  |  |  |   BETWEENFACTOR(Rot3) | 
					
						
							|  |  |  |   BETWEENFACTOR(Pose3) | 
					
						
							|  |  |  | } |