Style fixes as commented by @dellaert
parent
9561244b39
commit
7d7475b881
|
@ -25,27 +25,31 @@
|
||||||
|
|
||||||
#include <type_traits>
|
#include <type_traits>
|
||||||
|
|
||||||
#if __cplusplus <= 201103L
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
template<bool B, class T = void>
|
template<bool B, class T = void>
|
||||||
using enable_if_t = typename std::enable_if<B, T>::type;
|
using enable_if_t = typename std::enable_if<B, T>::type;
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
namespace gtsam {
|
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<T>
|
||||||
|
*/
|
||||||
template<typename T, typename ... Args>
|
template<typename T, typename ... Args>
|
||||||
gtsam::enable_if_t<has_custom_allocator<T>::value, boost::shared_ptr<T>> make_shared(Args&&... args)
|
gtsam::enable_if_t<needs_eigen_aligned_allocator<T>::value, boost::shared_ptr<T>> make_shared(Args &&... args) {
|
||||||
{
|
return boost::allocate_shared<T>(Eigen::aligned_allocator<T>(), std::forward<Args>(args)...);
|
||||||
return boost::allocate_shared<T>(Eigen::aligned_allocator<T>(), std::forward<Args> (args)...);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Fall back to the boost version if no need for alignment
|
/// Fall back to the boost version if no need for alignment
|
||||||
template<typename T, typename ... Args>
|
template<typename T, typename ... Args>
|
||||||
gtsam::enable_if_t<!has_custom_allocator<T>::value, boost::shared_ptr<T>> make_shared(Args&&... args)
|
gtsam::enable_if_t<!needs_eigen_aligned_allocator<T>::value, boost::shared_ptr<T>> make_shared(Args &&... args) {
|
||||||
{
|
return boost::make_shared<T>(std::forward<Args>(args)...);
|
||||||
return boost::make_shared<T>(std::forward<Args> (args)...);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
|
@ -233,27 +233,28 @@ namespace std {
|
||||||
|
|
||||||
namespace gtsam {
|
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<typename ...> 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
|
* This is required to make boost::make_shared and etc respect alignment, which is essential for the Python
|
||||||
* wrappers to work properly.
|
* wrappers to work properly.
|
||||||
*/
|
*/
|
||||||
#if __cplusplus < 201703L
|
|
||||||
template<typename ...> using void_t = void;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
template<typename, typename = void_t<>>
|
template<typename, typename = void_t<>>
|
||||||
struct has_custom_allocator : std::false_type {
|
struct needs_eigen_aligned_allocator : std::false_type {
|
||||||
};
|
};
|
||||||
template<typename T>
|
template<typename T>
|
||||||
struct has_custom_allocator<T, void_t<typename T::_custom_allocator_type_trait>> : std::true_type {
|
struct needs_eigen_aligned_allocator<T, void_t<typename T::_eigen_aligned_allocator_trait>> : 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 \
|
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW \
|
||||||
EIGEN_MAKE_ALIGNED_OPERATOR_NEW \
|
EIGEN_MAKE_ALIGNED_OPERATOR_NEW \
|
||||||
using _custom_allocator_type_trait = void;
|
using _eigen_aligned_allocator_trait = void;
|
||||||
|
|
Loading…
Reference in New Issue