Add comments
parent
7d7475b881
commit
6dbd7c243a
|
@ -26,16 +26,28 @@
|
|||
#include <type_traits>
|
||||
|
||||
namespace gtsam {
|
||||
/// An shorthand alias for accessing the ::type inside std::enable_if that can be used in a template directly
|
||||
template<bool B, class T = void>
|
||||
using enable_if_t = typename std::enable_if<B, T>::type;
|
||||
}
|
||||
|
||||
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.
|
||||
*
|
||||
* Explanation
|
||||
* ===============
|
||||
* The template `needs_eigen_aligned_allocator<T>::value` will evaluate to `std::true_type` if the type alias
|
||||
* `_eigen_aligned_allocator_trait = void` is present in a class, which is automatically added by the
|
||||
* `GTSAM_MAKE_ALIGNED_OPERATOR_NEW` macro.
|
||||
*
|
||||
* This function declaration will only be taken when the above condition is true, so if some object does not need to
|
||||
* be aligned, `gtsam::make_shared` will fall back to the next definition, which is a simple wrapper for
|
||||
* `boost::make_shared`.
|
||||
*
|
||||
* @tparam T The type of object being constructed
|
||||
* @tparam Args Type of the arguments of the constructor
|
||||
* @param args Arguments of the constructor
|
||||
|
|
|
@ -238,8 +238,18 @@ namespace gtsam {
|
|||
|
||||
/**
|
||||
* 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.
|
||||
*
|
||||
* Explanation
|
||||
* =============
|
||||
* When a GTSAM type is not declared with the type alias `_eigen_aligned_allocator_trait = void`, the first template
|
||||
* will be taken so `needs_eigen_aligned_allocator` will be resolved to `std::false_type`.
|
||||
*
|
||||
* Otherwise, it will resolve to the second template, which will be resolved to `std::true_type`.
|
||||
*
|
||||
* Please refer to `gtsam/base/make_shared.h` for an example.
|
||||
*/
|
||||
template<typename, typename = void_t<>>
|
||||
struct needs_eigen_aligned_allocator : std::false_type {
|
||||
|
@ -253,7 +263,7 @@ namespace gtsam {
|
|||
/**
|
||||
* 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
|
||||
* See https://eigen.tuxfamily.org/dox/group__DenseMatrixManipulation__Alignement.html for detailed explanation.
|
||||
*/
|
||||
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW \
|
||||
EIGEN_MAKE_ALIGNED_OPERATOR_NEW \
|
||||
|
|
Loading…
Reference in New Issue