38 #ifndef FCL_DATA_TYPES_H 39 #define FCL_DATA_TYPES_H 46 #include <Eigen/Dense> 47 #include <Eigen/StdVector> 48 #include "fcl/export.h" 78 template <
typename S,
int N>
82 using VectorX = Eigen::Matrix<S, Eigen::Dynamic, 1>;
91 using Transform3 = Eigen::Transform<S, 3, Eigen::Isometry>;
121 template <
typename _Tp>
124 template <
typename _Key,
typename _Tp,
typename _Compare = std::less<_Key>>
126 Eigen::aligned_allocator<std::pair<const _Key, _Tp>>>;
128 #if EIGEN_VERSION_AT_LEAST(3,2,9) 130 template <
typename _Tp,
typename... _Args>
133 typedef typename std::remove_const<_Tp>::type _Tp_nc;
134 return std::allocate_shared<_Tp>(Eigen::aligned_allocator<_Tp_nc>(),
135 std::forward<_Args>(__args)...);
163 :
std::allocator<T>() {}
166 :
std::allocator<T>(other) {}
170 :
std::allocator<T>(other) {}
176 Eigen::internal::check_size_for_overflow<T>(num);
177 return static_cast<pointer
>( Eigen::internal::aligned_malloc(num *
sizeof(T)) );
182 Eigen::internal::aligned_free(p);
186 template <
typename _Tp,
typename... _Args>
189 typedef typename std::remove_const<_Tp>::type _Tp_nc;
191 std::forward<_Args>(__args)...);
FCL_DEPRECATED std::uint32_t FCL_UINT32
FCL_DEPRECATED double FCL_REAL
FCL_DEPRECATED std::int64_t FCL_INT64
Eigen::Matrix< S, N, 1 > VectorN
Eigen::Quaternion< S > Quaternion
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
Transform3< double > Transform3d
Matrix3< float > Matrix3f
~aligned_allocator_cpp11()
Eigen::Matrix< S, 3, 3 > Matrix3
AngleAxis< float > AngleAxisf
FCL_DEPRECATED std::uint64_t FCL_UINT64
aligned_allocator_cpp11()
Eigen::Matrix< S, 3, 1 > Vector3
VectorN< float, N > VectorNf
Translation3< float > Translation3f
Eigen::AngleAxis< S > AngleAxis
VectorN< double, N > VectorNd
Aligned allocator that is compatible with c++11.
AngleAxis< double > AngleAxisd
FCL_DEPRECATED std::int32_t FCL_INT32
Eigen::Matrix< S, 6, 1 > Vector6
Eigen::Matrix< S, Eigen::Dynamic, 1 > VectorX
Transform3< float > Transform3f
VectorX< float > VectorXf
Vector3< double > Vector3d
Eigen::Matrix< S, 2, 1 > Vector2
Vector3< float > Vector3f
aligned_allocator_cpp11(const aligned_allocator_cpp11< U > &other)
std::shared_ptr< _Tp > make_aligned_shared(_Args &&... __args)
Translation3< double > Translation3d
aligned_allocator_cpp11< U > other
void deallocate(pointer p, size_type)
aligned_allocator_cpp11(const aligned_allocator_cpp11 &other)
Eigen::Translation< S, 3 > Translation3
VectorX< double > VectorXd
Quaternion< double > Quaterniond
Eigen::Matrix< S, 7, 1 > Vector7
std::map< _Key, _Tp, _Compare, Eigen::aligned_allocator< std::pair< const _Key, _Tp > >> aligned_map
Matrix3< double > Matrix3d
const T & const_reference
std::vector< _Tp, Eigen::aligned_allocator< _Tp > > aligned_vector
std::ptrdiff_t difference_type
pointer allocate(size_type num, const void *=0)
Quaternion< float > Quaternionf