33 #ifndef DART_MATH_MATHTYPES_HPP_
34 #define DART_MATH_MATHTYPES_HPP_
39 #include <Eigen/Dense>
53 const Eigen::Vector3d& _angular,
const Eigen::Vector3d& _linear)
56 composition << _angular, _linear;
66 #if EIGEN_VERSION_AT_LEAST(3, 2, 1) && EIGEN_VERSION_AT_MOST(3, 2, 8)
69 template <
typename _Tp>
71 = std::vector<_Tp, dart::common::detail::aligned_allocator_cpp11<_Tp>>;
74 template <
typename _Key,
typename _Tp,
typename _Compare = std::less<_Key>>
79 dart::common::detail::aligned_allocator_cpp11<std::pair<const _Key, _Tp>>>;
84 template <
typename _Tp>
88 template <
typename _Key,
typename _Tp,
typename _Compare = std::less<_Key>>
93 Eigen::aligned_allocator<std::pair<const _Key, _Tp>>>;
98 template <
typename _Tp,
typename... _Args>
103 std::forward<_Args>(__args)...);
114 using Jacobian = Eigen::Matrix<double, 6, Eigen::Dynamic>;
#define DART_DEPRECATED(version)
Definition: Deprecated.hpp:51
Definition: Random-impl.hpp:92
std::shared_ptr< _Tp > make_aligned_shared(_Args &&... __args)
Definition: MathTypes.hpp:100
Matrix< double, 6, 1 > Vector6d
Definition: MathTypes.hpp:49
std::vector< _Tp, Eigen::aligned_allocator< _Tp > > aligned_vector
Definition: MathTypes.hpp:85
Vector6d compose(const Eigen::Vector3d &_angular, const Eigen::Vector3d &_linear)
Definition: MathTypes.hpp:52
std::vector< Eigen::Vector3d > EIGEN_V_VEC3D
Definition: MathTypes.hpp:61
std::map< _Key, _Tp, _Compare, Eigen::aligned_allocator< std::pair< const _Key, _Tp > >> aligned_map
Definition: MathTypes.hpp:93
std::vector< std::vector< Eigen::Vector3d > > EIGEN_VV_VEC3D
Definition: MathTypes.hpp:64
Matrix< double, 6, 6 > Matrix6d
Definition: MathTypes.hpp:50
Eigen::Matrix< double, 6, Eigen::Dynamic > Jacobian
Definition: MathTypes.hpp:114
Eigen::Matrix< double, 3, Eigen::Dynamic > AngularJacobian
Definition: MathTypes.hpp:113
Eigen::Matrix< double, 3, Eigen::Dynamic > LinearJacobian
Definition: MathTypes.hpp:112
Eigen::Matrix6d Inertia
Definition: MathTypes.hpp:111
Definition: BulletCollisionDetector.cpp:65
Definition: SharedLibraryManager.hpp:46