diff --git a/gtsam.h b/gtsam.h index 614db91c7..cf232efa5 100644 --- a/gtsam.h +++ b/gtsam.h @@ -281,7 +281,7 @@ virtual class Value { }; #include -template +template virtual class GenericValue : gtsam::Value { void serializable() const; }; diff --git a/gtsam/base/make_shared.h b/gtsam/base/make_shared.h new file mode 100644 index 000000000..c8b63f5d4 --- /dev/null +++ b/gtsam/base/make_shared.h @@ -0,0 +1,44 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2020, Georgia Tech Research Corporation, + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @file make_shared.h + * @brief make_shared trampoline function to ensure proper alignment + * @author Fan Jiang + */ + +#pragma once + +#include +#include + +#include + +#include + +namespace gtsam { + + /** + * And our own `make_shared` as a layer of wrapping on `boost::make_shared` + */ + template + boost::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) + { + return boost::allocate_shared(Eigen::aligned_allocator(), std::forward (args)...); + } + + template + boost::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) + { + return boost::make_shared(std::forward (args)...); + } + +} \ No newline at end of file diff --git a/gtsam/base/types.h b/gtsam/base/types.h index 2fa6eebb6..3abbdfe81 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -230,3 +230,29 @@ namespace std { #ifdef ERROR #undef ERROR #endif + +namespace gtsam { + + /** + * A trait to mark classes that need special alignment. + * Please refer to https://github.com/PointCloudLibrary/pcl/pull/3163 + */ +#if __cplusplus < 201703L + template using void_t = void; +#endif + + template> + struct has_custom_allocator : std::false_type { + }; + template + struct has_custom_allocator> : std::true_type { + }; + +} + +/** + * This is necessary for the Cython wrapper to work properly, and possibly reduce future misalignment problems. + */ +#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW \ + EIGEN_MAKE_ALIGNED_OPERATOR_NEW \ + using _custom_allocator_type_trait = void; \ No newline at end of file diff --git a/gtsam/geometry/SOn.h b/gtsam/geometry/SOn.h index 5313d3018..767b12020 100644 --- a/gtsam/geometry/SOn.h +++ b/gtsam/geometry/SOn.h @@ -20,8 +20,8 @@ #include #include +#include #include - #include #include // TODO(frank): how to avoid? @@ -54,7 +54,7 @@ class SO : public LieGroup, internal::DimensionSO(N)> { using VectorN2 = Eigen::Matrix; using MatrixDD = Eigen::Matrix; - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW protected: MatrixNN matrix_; ///< Rotation matrix diff --git a/wrap/Module.cpp b/wrap/Module.cpp index a7db9e1f6..ec02dc412 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -350,7 +350,10 @@ void Module::emit_cython_pxd(FileWriter& pxdFile) const { " T* get()\n" " long use_count() const\n" " T& operator*()\n\n" - " cdef shared_ptr[T] dynamic_pointer_cast[T,U](const shared_ptr[U]& r)\n" + " cdef shared_ptr[T] dynamic_pointer_cast[T,U](const shared_ptr[U]& r)\n\n"; + + // gtsam alignment-friendly shared_ptr + pxdFile.oss << "cdef extern from \"gtsam/base/make_shared.h\" namespace \"gtsam\":\n" " cdef shared_ptr[T] make_shared[T](const T& r)\n\n"; for(const TypedefPair& types: typedefs)