6 #ifndef __pinocchio_motion_tpl_hpp__ 7 #define __pinocchio_motion_tpl_hpp__ 11 template<
typename _Scalar,
int _Options>
15 typedef Eigen::Matrix<Scalar,3,1,_Options>
Vector3;
16 typedef Eigen::Matrix<Scalar,6,1,_Options>
Vector6;
17 typedef Eigen::Matrix<Scalar,4,4,_Options>
Matrix4;
18 typedef Eigen::Matrix<Scalar,6,6,_Options>
Matrix6;
23 typedef typename Vector6::template FixedSegmentReturnType<3>::Type
LinearType;
24 typedef typename Vector6::template FixedSegmentReturnType<3>::Type
AngularType;
25 typedef typename Vector6::template ConstFixedSegmentReturnType<3>::Type
ConstLinearType;
26 typedef typename Vector6::template ConstFixedSegmentReturnType<3>::Type
ConstAngularType;
38 template<
typename _Scalar,
int _Options>
42 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
47 using Base::operator=;
52 using Base::__opposite__;
53 using Base::__minus__;
61 template<
typename V1,
typename V2>
62 MotionTpl(
const Eigen::MatrixBase<V1> &
v,
const Eigen::MatrixBase<V2> &
w)
64 assert(v.size() == 3);
65 assert(w.size() == 3);
66 linear() =
v; angular() =
w;
73 EIGEN_STATIC_ASSERT_VECTOR_ONLY(V6);
74 assert(v.size() == 6);
79 : m_data(clone.toVector())
94 inline PlainReturnType
plain()
const {
return *
this; }
100 ConstAngularType
angular_impl()
const {
return m_data.template segment<3> (ANGULAR); }
101 ConstLinearType
linear_impl()
const {
return m_data.template segment<3> (LINEAR); }
102 AngularType
angular_impl() {
return m_data.template segment<3> (ANGULAR); }
103 LinearType
linear_impl() {
return m_data.template segment<3> (LINEAR); }
105 template<
typename V3>
108 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(V3,3);
111 template<
typename V3>
114 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(V3,3);
121 {
return MotionPlain(m_data+v.
toVector()); }
123 template<
typename Vector6ArgType>
125 {
return MotionPlain(m_data+v.
toVector()); }
129 {
return MotionPlain(m_data-v.
toVector()); }
131 template<
typename Vector6ArgType>
133 {
return MotionPlain(m_data-v.
toVector()); }
137 { m_data += v.
toVector();
return *
this; }
139 template<
typename Vector6ArgType>
141 { m_data += v.
toVector();
return *
this; }
145 { m_data -= v.
toVector();
return *
this; }
147 template<
typename Vector6ArgType>
149 { m_data -= v.
toVector();
return *
this; }
151 template<
typename OtherScalar>
152 MotionPlain
__mult__(
const OtherScalar & alpha)
const 153 {
return MotionPlain(alpha*m_data); }
158 template<
typename NewScalar>
162 ReturnType
res(linear().
template cast<NewScalar>(),
163 angular().
template cast<NewScalar>());
174 #endif // ifndef __pinocchio_motion_tpl_hpp__
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
MotionTpl & __pequ__(const MotionRef< Vector6ArgType > &v)
Eigen::Matrix< Scalar, 4, 4, _Options > Matrix4
MotionTpl(const MotionTpl< Scalar, O2 > &clone)
MotionTpl & __mequ__(const MotionTpl< Scalar, O2 > &v)
Eigen::Matrix< Scalar, 6, 1, _Options > Vector6
void angular_impl(const Eigen::MatrixBase< V3 > &w)
virtual CollisionGeometry * clone() const=0
MotionTpl(const MotionBase< M2 > &clone)
ConstAngularType angular_impl() const
#define MOTION_TYPEDEF_TPL(Derived)
PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like) operator*(const Eigen
MotionTpl & __mequ__(const MotionRef< Vector6ArgType > &v)
ToVectorConstReturnType toVector_impl() const
ToVectorReturnType toVector_impl()
ConstLinearType linear() const
MotionTpl< NewScalar, Options > cast() const
MotionPlain __plus__(const MotionTpl< Scalar, O2 > &v) const
ConstLinearType linear_impl() const
ConstAngularType angular() const
Vector6::template ConstFixedSegmentReturnType< 3 >::Type ConstAngularType
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef MotionDense< MotionTpl > Base
Eigen::Matrix< Scalar, 3, 1, _Options > Vector3
MotionPlain __mult__(const OtherScalar &alpha) const
Matrix4 HomogeneousMatrixType
Vector6::template ConstFixedSegmentReturnType< 3 >::Type ConstLinearType
Vector6::template FixedSegmentReturnType< 3 >::Type LinearType
Vector6::template FixedSegmentReturnType< 3 >::Type AngularType
MotionTpl(const Eigen::MatrixBase< V1 > &v, const Eigen::MatrixBase< V2 > &w)
const MotionPlain & PlainReturnType
#define PINOCCHIO_EIGEN_REF_TYPE(D)
PlainReturnType plain() const
void linear_impl(const Eigen::MatrixBase< V3 > &v)
Main pinocchio namespace.
MotionPlain __minus__(const MotionRef< Vector6ArgType > &v) const
ToVectorConstReturnType toVector() const
MotionTpl(const Eigen::MatrixBase< V6 > &v)
MotionRef< Vector6 > ref()
MotionRef< Vector6 > MotionRefType
Common traits structure to fully define base classes for CRTP.
MotionPlain __minus__(const MotionTpl< Scalar, O2 > &v) const
MotionTpl< Scalar, _Options > MotionPlain
MotionTpl & __pequ__(const MotionTpl< Scalar, O2 > &v)
static MotionTpl Random()
AngularType angular_impl()
Eigen::Matrix< Scalar, 6, 6, _Options > Matrix6
MotionPlain __plus__(const MotionRef< Vector6ArgType > &v) const
MotionTpl(const MotionDense< M2 > &clone)