commit
						a350295760
					
				| 
						 | 
				
			
			@ -13,6 +13,7 @@
 | 
			
		|||
#include <pybind11/eigen.h>
 | 
			
		||||
#include <pybind11/stl_bind.h>
 | 
			
		||||
#include <pybind11/pybind11.h>
 | 
			
		||||
#include "gtsam/config.h"
 | 
			
		||||
#include "gtsam/base/serialization.h"
 | 
			
		||||
#include "gtsam/nonlinear/utilities.h"  // for RedirectCout.
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -1,6 +1,13 @@
 | 
			
		|||
// Please refer to: https://pybind11.readthedocs.io/en/stable/advanced/cast/stl.html
 | 
			
		||||
// These are required to save one copy operation on Python calls
 | 
			
		||||
#ifdef GTSAM_ALLOCATOR_TBB
 | 
			
		||||
PYBIND11_MAKE_OPAQUE(std::vector<gtsam::Key, tbb::tbb_allocator<gtsam::Key>>);
 | 
			
		||||
PYBIND11_MAKE_OPAQUE(std::vector<gtsam::Point2, Eigen::aligned_allocator<gtsam::Point2> >);
 | 
			
		||||
PYBIND11_MAKE_OPAQUE(std::vector<gtsam::Pose3>);
 | 
			
		||||
PYBIND11_MAKE_OPAQUE(std::vector<gtsam::BetweenFactor<gtsam::Pose3>>);
 | 
			
		||||
#else
 | 
			
		||||
PYBIND11_MAKE_OPAQUE(std::vector<gtsam::Key>);
 | 
			
		||||
PYBIND11_MAKE_OPAQUE(std::vector<gtsam::Point2, Eigen::aligned_allocator<gtsam::Point2> >);
 | 
			
		||||
PYBIND11_MAKE_OPAQUE(std::vector<gtsam::Pose3>);
 | 
			
		||||
PYBIND11_MAKE_OPAQUE(std::vector<gtsam::BetweenFactor<gtsam::Pose3>>);
 | 
			
		||||
#endif
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -1,6 +1,13 @@
 | 
			
		|||
// Please refer to: https://pybind11.readthedocs.io/en/stable/advanced/cast/stl.html
 | 
			
		||||
// These are required to save one copy operation on Python calls
 | 
			
		||||
#ifdef GTSAM_ALLOCATOR_TBB
 | 
			
		||||
py::bind_vector<std::vector<gtsam::Key, tbb::tbb_allocator<gtsam::Key> > >(m_, "KeyVector");
 | 
			
		||||
py::bind_vector<std::vector<gtsam::Point2, Eigen::aligned_allocator<gtsam::Point2> > >(m_, "Point2Vector");
 | 
			
		||||
py::bind_vector<std::vector<gtsam::Pose3> >(m_, "Pose3Vector");
 | 
			
		||||
py::bind_vector<std::vector<boost::shared_ptr<gtsam::BetweenFactor<gtsam::Pose3> > > >(m_, "BetweenFactorPose3s");
 | 
			
		||||
#else
 | 
			
		||||
py::bind_vector<std::vector<gtsam::Key> >(m_, "KeyVector");
 | 
			
		||||
py::bind_vector<std::vector<gtsam::Point2, Eigen::aligned_allocator<gtsam::Point2> > >(m_, "Point2Vector");
 | 
			
		||||
py::bind_vector<std::vector<gtsam::Pose3> >(m_, "Pose3Vector");
 | 
			
		||||
py::bind_vector<std::vector<boost::shared_ptr<gtsam::BetweenFactor<gtsam::Pose3> > > >(m_, "BetweenFactorPose3s");
 | 
			
		||||
py::bind_vector<std::vector<boost::shared_ptr<gtsam::BetweenFactor<gtsam::Pose3> > > >(m_, "BetweenFactorPose3s");
 | 
			
		||||
#endif
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
		Loading…
	
		Reference in New Issue