diff --git a/gtsam/base/make_shared.h b/gtsam/base/make_shared.h index 966dd516d..c7d98cdee 100644 --- a/gtsam/base/make_shared.h +++ b/gtsam/base/make_shared.h @@ -25,27 +25,31 @@ #include -#if __cplusplus <= 201103L namespace gtsam { template using enable_if_t = typename std::enable_if::type; } -#endif namespace gtsam { - /// Add our own `make_shared` as a layer of wrapping on `boost::make_shared` + /** Add our own `make_shared` as a layer of wrapping on `boost::make_shared` + * This solves the problem with the stock `make_shared` that custom alignment is not respected, causing SEGFAULTs + * at runtime, which is notoriously hard to debug. + * + * @tparam T The type of object being constructed + * @tparam Args Type of the arguments of the constructor + * @param args Arguments of the constructor + * @return The object created as a boost::shared_ptr + */ template - gtsam::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) - { - return boost::allocate_shared(Eigen::aligned_allocator(), std::forward (args)...); + gtsam::enable_if_t::value, boost::shared_ptr> make_shared(Args &&... args) { + return boost::allocate_shared(Eigen::aligned_allocator(), std::forward(args)...); } /// Fall back to the boost version if no need for alignment template - gtsam::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) - { - return boost::make_shared(std::forward (args)...); + gtsam::enable_if_t::value, boost::shared_ptr> make_shared(Args &&... args) { + return boost::make_shared(std::forward(args)...); } } diff --git a/gtsam/base/types.h b/gtsam/base/types.h index 93c475c40..a4b2fb6ea 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -233,27 +233,28 @@ namespace std { namespace gtsam { + /// Convenience void_t as we assume C++11, it will not conflict the std one in C++17 as this is in `gtsam::` + template using void_t = void; + /** - * A trait to mark classes that need special alignment. + * A SFINAE trait to mark classes that need special alignment. * This is required to make boost::make_shared and etc respect alignment, which is essential for the Python * wrappers to work properly. */ -#if __cplusplus < 201703L - template using void_t = void; -#endif - template> - struct has_custom_allocator : std::false_type { + struct needs_eigen_aligned_allocator : std::false_type { }; template - struct has_custom_allocator> : std::true_type { + struct needs_eigen_aligned_allocator> : std::true_type { }; } /** - * This is necessary for the Cython wrapper to work properly, and possibly reduce future misalignment problems. + * This marks a GTSAM object to require alignment. With this macro an object will automatically be allocated in aligned + * memory when one uses `gtsam::make_shared`. It reduces future misalignment problems that is hard to debug. + * See https://eigen.tuxfamily.org/dox/group__DenseMatrixManipulation__Alignement.html for details */ #define GTSAM_MAKE_ALIGNED_OPERATOR_NEW \ EIGEN_MAKE_ALIGNED_OPERATOR_NEW \ - using _custom_allocator_type_trait = void; \ No newline at end of file + using _eigen_aligned_allocator_trait = void;