6 #ifndef __pinocchio_force_tpl_hpp__ 7 #define __pinocchio_force_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,6,6,_Options>
Matrix6;
20 typedef typename Vector6::template FixedSegmentReturnType<3>::Type
LinearType;
21 typedef typename Vector6::template FixedSegmentReturnType<3>::Type
AngularType;
22 typedef typename Vector6::template ConstFixedSegmentReturnType<3>::Type
ConstLinearType;
23 typedef typename Vector6::template ConstFixedSegmentReturnType<3>::Type
ConstAngularType;
34 template<
typename _Scalar,
int _Options>
38 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
43 using Base::operator=;
44 using Base::operator!=;
51 template<
typename V1,
typename V2>
52 ForceTpl(
const Eigen::MatrixBase<V1> &
v,
const Eigen::MatrixBase<V2> &
w)
54 assert(v.size() == 3);
55 assert(w.size() == 3);
56 linear() =
v; angular() =
w;
63 EIGEN_STATIC_ASSERT_VECTOR_ONLY(V6);
64 assert(v.size() == 6);
68 : m_data(clone.toVector())
79 : m_data(clone.toVector())
94 ConstAngularType
angular_impl()
const {
return m_data.template segment<3> (ANGULAR); }
95 ConstLinearType
linear_impl()
const {
return m_data.template segment<3> (LINEAR); }
96 AngularType
angular_impl() {
return m_data.template segment<3> (ANGULAR); }
97 LinearType
linear_impl() {
return m_data.template segment<3> (LINEAR); }
102 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(V3,3);
105 template<
typename V3>
108 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(V3,3);
115 template<
typename NewScalar>
119 ReturnType
res(linear().
template cast<NewScalar>(),
120 angular().
template cast<NewScalar>());
131 #endif // ifndef __pinocchio_force_tpl_hpp__ Vector6::template ConstFixedSegmentReturnType< 3 >::Type ConstLinearType
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
ToVectorConstReturnType toVector_impl() const
ConstAngularType angular_impl() const
Vector6::template FixedSegmentReturnType< 3 >::Type LinearType
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef ForceDense< ForceTpl > Base
PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like) operator*(const Eigen
ToVectorConstReturnType toVector() const
Return the force as an Eigen vector.
Eigen::Matrix< Scalar, 6, 1, _Options > Vector6
ForceRef< Vector6 > ForceRefType
ConstAngularType angular() const
Return the angular part of the force vector.
ForceTpl(const ForceDense< M2 > &clone)
ForceTpl(const ForceTpl &clone)
ConstLinearType linear() const
Return the linear part of the force vector.
Eigen::Matrix< Scalar, 6, 6, _Options > Matrix6
#define FORCE_TYPEDEF_TPL(Derived)
Vector6::template ConstFixedSegmentReturnType< 3 >::Type ConstAngularType
ToVectorReturnType toVector_impl()
ForceTpl< NewScalar, Options > cast() const
ForceRef< Vector6 > ref()
#define PINOCCHIO_EIGEN_REF_TYPE(D)
Main pinocchio namespace.
void linear_impl(const Eigen::MatrixBase< V3 > &v)
ForceTpl & operator=(const ForceTpl &clone)
ForceTpl(const Eigen::MatrixBase< V1 > &v, const Eigen::MatrixBase< V2 > &w)
ForceTpl(const ForceTpl< Scalar, O2 > &clone)
Common traits structure to fully define base classes for CRTP.
Vector6::template FixedSegmentReturnType< 3 >::Type AngularType
AngularType angular_impl()
Eigen::Matrix< Scalar, 3, 1, _Options > Vector3
void angular_impl(const Eigen::MatrixBase< V3 > &w)
ConstLinearType linear_impl() const
ForceTpl(const Eigen::MatrixBase< V6 > &v)