diff --git a/python/gtsam/preamble.h b/python/gtsam/preamble.h index 0a1199122..b67df2644 100644 --- a/python/gtsam/preamble.h +++ b/python/gtsam/preamble.h @@ -2,12 +2,9 @@ // 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); +#endif 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 2bd6a98a1..950dd8236 100644 --- a/python/gtsam/specializations.h +++ b/python/gtsam/specializations.h @@ -2,12 +2,9 @@ // 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"); +#endif py::bind_vector > >(m_, "Point2Vector"); py::bind_vector >(m_, "Pose3Vector"); py::bind_vector > > >(m_, "BetweenFactorPose3s"); -#endif