diff --git a/python/gtsam/gtsam.tpl b/python/gtsam/gtsam.tpl index 065486c3c..634a81e90 100644 --- a/python/gtsam/gtsam.tpl +++ b/python/gtsam/gtsam.tpl @@ -13,6 +13,7 @@ #include #include #include +#include "gtsam/config.h" #include "gtsam/base/serialization.h" #include "gtsam/nonlinear/utilities.h" // for RedirectCout. diff --git a/python/gtsam/preamble.h b/python/gtsam/preamble.h index 6542343cb..0a1199122 100644 --- a/python/gtsam/preamble.h +++ b/python/gtsam/preamble.h @@ -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>); +PYBIND11_MAKE_OPAQUE(std::vector >); +PYBIND11_MAKE_OPAQUE(std::vector); +PYBIND11_MAKE_OPAQUE(std::vector>); +#else PYBIND11_MAKE_OPAQUE(std::vector); PYBIND11_MAKE_OPAQUE(std::vector >); PYBIND11_MAKE_OPAQUE(std::vector); PYBIND11_MAKE_OPAQUE(std::vector>); +#endif diff --git a/python/gtsam/specializations.h b/python/gtsam/specializations.h index e23534c85..4af8b7383 100644 --- a/python/gtsam/specializations.h +++ b/python/gtsam/specializations.h @@ -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 > >(m_, "KeyVector"); +py::bind_vector > >(m_, "Point2Vector"); +py::bind_vector >(m_, "Pose3Vector"); +py::bind_vector > > >(m_, "BetweenFactorPose3s"); +#else py::bind_vector >(m_, "KeyVector"); py::bind_vector > >(m_, "Point2Vector"); py::bind_vector >(m_, "Pose3Vector"); -py::bind_vector > > >(m_, "BetweenFactorPose3s"); \ No newline at end of file +py::bind_vector > > >(m_, "BetweenFactorPose3s"); +#endif \ No newline at end of file