6 #ifndef __pinocchio_multibody_joint_spherical_ZYX_hpp__
7 #define __pinocchio_multibody_joint_spherical_ZYX_hpp__
20 template<
typename Scalar,
int Options>
23 template<
typename _Scalar,
int _Options>
40 typedef Eigen::Matrix<Scalar, 6, 3, Options>
DenseBase;
49 template<
typename _Scalar,
int _Options>
53 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
61 typedef Eigen::Matrix<Scalar, 3, 3, Options>
Matrix3;
67 template<
typename Matrix3Like>
71 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix3Like, 3, 3);
74 template<
typename Vector3Like>
75 JointMotion
__mult__(
const Eigen::MatrixBase<Vector3Like> &
v)
const
77 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3);
78 return JointMotion(
m_S *
v);
104 template<
typename Derived>
106 Eigen::Transpose<const Matrix3>,
107 Eigen::Block<const typename ForceDense<Derived>::Vector6, 3, 1>>
::type
116 typename Eigen::Transpose<const Matrix3>,
117 typename Eigen::MatrixBase<const D>::template NRowsBlockXpr<3>::Type>
::type
121 D::RowsAtCompileTime == 6, THIS_METHOD_IS_ONLY_FOR_MATRICES_OF_A_SPECIFIC_SIZE)
122 return ref.
m_S.transpose() * F.template middleRows<3>(ANGULAR);
134 S.template middleRows<3>(LINEAR).setZero();
135 S.template middleRows<3>(ANGULAR) =
m_S;
143 template<
typename S1,
int O1>
152 Eigen::Matrix<Scalar, 6, 3, Options> result;
155 result.template middleRows<3>(ANGULAR).noalias() =
m.rotation() *
m_S;
159 m.translation(), result.template middleRows<3>(Motion::ANGULAR),
160 result.template middleRows<3>(LINEAR));
165 template<
typename S1,
int O1>
168 Eigen::Matrix<Scalar, 6, 3, Options> result;
171 cross(
m.translation(),
m_S, result.template middleRows<3>(ANGULAR));
172 result.template middleRows<3>(LINEAR).noalias() =
173 -
m.rotation().transpose() * result.template middleRows<3>(ANGULAR);
176 result.template middleRows<3>(ANGULAR).noalias() =
m.rotation().transpose() *
m_S;
181 template<
typename MotionDerived>
184 const typename MotionDerived::ConstLinearType
v =
m.linear();
185 const typename MotionDerived::ConstAngularType
w =
m.angular();
215 template<
typename Scalar,
int Options>
223 return constraint.
matrix().transpose() * constraint.
matrix();
229 template<
typename S1,
int O1,
typename S2,
int O2>
230 Eigen::Matrix<S1, 6, 3, O1>
235 Eigen::Matrix<S1, 6, 3, O1>
M;
236 alphaSkew(-
Y.mass(),
Y.lever(),
M.template middleRows<3>(Constraint::LINEAR));
237 M.template middleRows<3>(Constraint::ANGULAR) =
238 (
Y.inertia() -
typename Symmetric3::AlphaSkewSquare(
Y.mass(),
Y.lever())).matrix();
240 return (
M *
S.angularSubspace()).eval();
245 template<
typename Matrix6Like,
typename S2,
int O2>
246 const typename MatrixMatrixProduct<
247 typename Eigen::internal::remove_const<
248 typename SizeDepType<3>::ColsReturn<Matrix6Like>::ConstType>
::type,
253 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix6Like, 6, 6);
254 return Y.derived().template middleCols<3>(Inertia::ANGULAR) *
S.angularSubspace();
257 template<
typename S1,
int O1>
267 template<
typename S1,
int O1,
typename MotionDerived>
273 template<
typename Scalar,
int Options>
276 template<
typename _Scalar,
int _Options>
297 typedef Eigen::Matrix<Scalar, 6, NV, Options>
U_t;
298 typedef Eigen::Matrix<Scalar, NV, NV, Options>
D_t;
299 typedef Eigen::Matrix<Scalar, 6, NV, Options>
UD_t;
307 template<
typename _Scalar,
int _Options>
314 template<
typename _Scalar,
int _Options>
321 template<
typename _Scalar,
int _Options>
323 :
public JointDataBase<JointDataSphericalZYXTpl<_Scalar, _Options>>
325 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
345 :
joint_q(ConfigVector_t::Zero())
346 ,
joint_v(TangentVector_t::Zero())
347 ,
S(Constraint_t::Matrix3::Zero())
348 ,
M(Transformation_t::Identity())
353 ,
UDinv(UD_t::Zero())
360 return std::string(
"JointDataSphericalZYX");
370 template<
typename _Scalar,
int _Options>
371 struct JointModelSphericalZYXTpl
372 :
public JointModelBase<JointModelSphericalZYXTpl<_Scalar, _Options>>
374 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
386 return JointDataDerived();
391 return {
true,
true,
true};
396 return {
true,
true,
true};
399 template<
typename ConfigVector>
400 void calc(JointDataDerived &
data,
const typename Eigen::MatrixBase<ConfigVector> &
qs)
const
411 data.M.rotation() << c0 * c1, c0 * s1 * s2 - s0 *
c2, c0 * s1 *
c2 + s0 * s2, s0 * c1,
412 s0 * s1 * s2 + c0 *
c2, s0 * s1 *
c2 - c0 * s2, -s1, c1 * s2, c1 *
c2;
418 template<
typename TangentVector>
420 calc(JointDataDerived &
data,
const Blank,
const typename Eigen::MatrixBase<TangentVector> & vs)
423 data.joint_v = vs.template segment<NV>(
idx_v());
424 data.v().noalias() =
data.S.angularSubspace() *
data.joint_v;
435 template<
typename ConfigVector,
typename TangentVector>
437 JointDataDerived &
data,
438 const typename Eigen::MatrixBase<ConfigVector> &
qs,
439 const typename Eigen::MatrixBase<TangentVector> & vs)
const
450 data.M.rotation() << c0 * c1, c0 * s1 * s2 - s0 *
c2, c0 * s1 *
c2 + s0 * s2, s0 * c1,
451 s0 * s1 * s2 + c0 *
c2, s0 * s1 *
c2 - c0 * s2, -s1, c1 * s2, c1 *
c2;
456 data.joint_v = vs.template segment<NV>(
idx_v());
457 data.v().noalias() =
data.S.angularSubspace() *
data.joint_v;
459 #define q_dot data.joint_v
468 template<
typename VectorLike,
typename Matrix6Like>
470 JointDataDerived &
data,
471 const Eigen::MatrixBase<VectorLike> & armature,
472 const Eigen::MatrixBase<Matrix6Like> & I,
473 const bool update_I)
const
475 data.U.noalias() = I.template middleCols<3>(Motion::ANGULAR) *
data.S.angularSubspace();
477 data.S.angularSubspace().transpose() *
data.U.template middleRows<3>(Motion::ANGULAR);
478 data.StU.diagonal() += armature;
490 return std::string(
"JointModelSphericalZYX");
498 template<
typename NewScalar>
511 #include <boost/type_traits.hpp>
515 template<
typename Scalar,
int Options>
517 :
public integral_constant<bool, true>
521 template<
typename Scalar,
int Options>
523 :
public integral_constant<bool, true>
527 template<
typename Scalar,
int Options>
529 :
public integral_constant<bool, true>
533 template<
typename Scalar,
int Options>
535 :
public integral_constant<bool, true>
540 #endif // ifndef __pinocchio_multibody_joint_spherical_ZYX_hpp__