| 
									
										
										
										
											2015-11-20 01:31:38 +08:00
										 |  |  | /* ----------------------------------------------------------------------------
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-01-28 17:31:44 +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 Values class to python | 
					
						
							|  |  |  |  * @author Ellon Paiva Mendes (LAAS-CNRS) | 
					
						
							|  |  |  |  **/ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											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>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-11-20 01:31:38 +08:00
										 |  |  | #include "gtsam/nonlinear/Values.h"
 | 
					
						
							| 
									
										
										
										
											2016-01-25 16:58:08 +08:00
										 |  |  | #include "gtsam/geometry/Point2.h"
 | 
					
						
							|  |  |  | #include "gtsam/geometry/Rot2.h"
 | 
					
						
							|  |  |  | #include "gtsam/geometry/Pose2.h"
 | 
					
						
							| 
									
										
										
										
											2015-11-20 01:31:38 +08:00
										 |  |  | #include "gtsam/geometry/Point3.h"
 | 
					
						
							|  |  |  | #include "gtsam/geometry/Rot3.h"
 | 
					
						
							|  |  |  | #include "gtsam/geometry/Pose3.h"
 | 
					
						
							| 
									
										
										
										
											2016-01-28 17:31:44 +08:00
										 |  |  | #include "gtsam/navigation/ImuBias.h"
 | 
					
						
							| 
									
										
										
										
											2016-02-25 03:01:19 +08:00
										 |  |  | #include "gtsam/navigation/NavState.h"
 | 
					
						
							| 
									
										
										
										
											2013-11-20 10:30:44 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace boost::python; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-01-25 16:58:08 +08:00
										 |  |  | BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, Values::print, 0, 1); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-11-20 10:30:44 +08:00
										 |  |  | void exportValues(){ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-01-28 17:31:44 +08:00
										 |  |  |   typedef imuBias::ConstantBias Bias; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-11-20 10:30:44 +08:00
										 |  |  |   bool (Values::*exists1)(Key) const = &Values::exists; | 
					
						
							| 
									
										
										
										
											2016-01-25 16:58:08 +08:00
										 |  |  |   void  (Values::*insert_point2)(Key, const gtsam::Point2&) = &Values::insert; | 
					
						
							|  |  |  |   void  (Values::*insert_rot2)  (Key, const gtsam::Rot2&) = &Values::insert; | 
					
						
							|  |  |  |   void  (Values::*insert_pose2) (Key, const gtsam::Pose2&) = &Values::insert; | 
					
						
							| 
									
										
										
										
											2015-11-20 01:31:38 +08:00
										 |  |  |   void  (Values::*insert_point3)(Key, const gtsam::Point3&) = &Values::insert; | 
					
						
							|  |  |  |   void  (Values::*insert_rot3)  (Key, const gtsam::Rot3&) = &Values::insert; | 
					
						
							|  |  |  |   void  (Values::*insert_pose3) (Key, const gtsam::Pose3&) = &Values::insert; | 
					
						
							| 
									
										
										
										
											2016-01-28 17:31:44 +08:00
										 |  |  |   void  (Values::*insert_bias) (Key, const Bias&) = &Values::insert; | 
					
						
							| 
									
										
										
										
											2016-02-25 03:01:19 +08:00
										 |  |  |   void  (Values::*insert_navstate) (Key, const NavState&) = &Values::insert; | 
					
						
							| 
									
										
										
										
											2016-06-19 14:13:59 +08:00
										 |  |  |   void  (Values::*insert_vector) (Key, const gtsam::Vector&) = &Values::insert; | 
					
						
							|  |  |  |   void  (Values::*insert_vector2) (Key, const gtsam::Vector2&) = &Values::insert; | 
					
						
							| 
									
										
										
										
											2016-01-28 17:31:44 +08:00
										 |  |  |   void  (Values::*insert_vector3) (Key, const gtsam::Vector3&) = &Values::insert; | 
					
						
							| 
									
										
										
										
											2016-01-25 16:58:08 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-11-20 10:30:44 +08:00
										 |  |  |   class_<Values>("Values", init<>()) | 
					
						
							|  |  |  |   .def(init<Values>()) | 
					
						
							| 
									
										
										
										
											2015-11-20 01:31:38 +08:00
										 |  |  |   .def("clear", &Values::clear) | 
					
						
							|  |  |  |   .def("dim", &Values::dim) | 
					
						
							|  |  |  |   .def("empty", &Values::empty) | 
					
						
							|  |  |  |   .def("equals", &Values::equals) | 
					
						
							|  |  |  |   .def("erase", &Values::erase) | 
					
						
							| 
									
										
										
										
											2016-01-25 16:58:08 +08:00
										 |  |  |   .def("print", &Values::print, print_overloads(args("s"))) | 
					
						
							| 
									
										
										
										
											2015-11-20 01:31:38 +08:00
										 |  |  |   .def("size", &Values::size) | 
					
						
							|  |  |  |   .def("swap", &Values::swap) | 
					
						
							| 
									
										
										
										
											2016-01-25 16:58:08 +08:00
										 |  |  |   .def("insert", insert_point2) | 
					
						
							|  |  |  |   .def("insert", insert_rot2) | 
					
						
							|  |  |  |   .def("insert", insert_pose2) | 
					
						
							| 
									
										
										
										
											2015-11-20 01:31:38 +08:00
										 |  |  |   .def("insert", insert_point3) | 
					
						
							|  |  |  |   .def("insert", insert_rot3) | 
					
						
							|  |  |  |   .def("insert", insert_pose3) | 
					
						
							| 
									
										
										
										
											2016-01-28 17:31:44 +08:00
										 |  |  |   .def("insert", insert_bias) | 
					
						
							| 
									
										
										
										
											2016-02-25 03:01:19 +08:00
										 |  |  |   .def("insert", insert_navstate) | 
					
						
							| 
									
										
										
										
											2016-06-19 14:13:59 +08:00
										 |  |  |   .def("insert", insert_vector) | 
					
						
							|  |  |  |   .def("insert", insert_vector2) | 
					
						
							| 
									
										
										
										
											2016-01-28 17:31:44 +08:00
										 |  |  |   .def("insert", insert_vector3) | 
					
						
							| 
									
										
										
										
											2016-04-11 09:30:41 +08:00
										 |  |  |   .def("atPoint2", &Values::at<Point2>) | 
					
						
							|  |  |  |   .def("atRot2", &Values::at<Rot2>) | 
					
						
							|  |  |  |   .def("atPose2", &Values::at<Pose2>) | 
					
						
							|  |  |  |   .def("atPoint3", &Values::at<Point3>) | 
					
						
							|  |  |  |   .def("atRot3", &Values::at<Rot3>) | 
					
						
							|  |  |  |   .def("atPose3", &Values::at<Pose3>) | 
					
						
							|  |  |  |   .def("atConstantBias", &Values::at<Bias>) | 
					
						
							|  |  |  |   .def("atNavState", &Values::at<NavState>) | 
					
						
							| 
									
										
										
										
											2016-06-19 14:13:59 +08:00
										 |  |  |   .def("atVector", &Values::at<Vector>) | 
					
						
							|  |  |  |   .def("atVector2", &Values::at<Vector2>) | 
					
						
							| 
									
										
										
										
											2016-04-11 09:30:41 +08:00
										 |  |  |   .def("atVector3", &Values::at<Vector3>) | 
					
						
							| 
									
										
										
										
											2013-11-20 10:30:44 +08:00
										 |  |  |   .def("exists", exists1) | 
					
						
							| 
									
										
										
										
											2015-11-24 20:28:01 +08:00
										 |  |  |   .def("keys", &Values::keys) | 
					
						
							| 
									
										
										
										
											2013-11-20 10:30:44 +08:00
										 |  |  |   ; | 
					
						
							| 
									
										
										
										
											2016-01-25 16:58:08 +08:00
										 |  |  | } |