6 #ifndef __pinocchio_joint_spherical_hpp__ 7 #define __pinocchio_joint_spherical_hpp__ 9 #include "pinocchio/macros.hpp" 10 #include "pinocchio/multibody/joint/joint-base.hpp" 11 #include "pinocchio/multibody/constraint.hpp" 12 #include "pinocchio/math/sincos.hpp" 13 #include "pinocchio/spatial/inertia.hpp" 14 #include "pinocchio/spatial/skew.hpp" 22 template<
typename Scalar,
int Options>
28 template<
typename Scalar,
int Options,
typename MotionDerived>
34 template<
typename _Scalar,
int _Options>
37 typedef _Scalar Scalar;
38 enum { Options = _Options };
39 typedef Eigen::Matrix<Scalar,3,1,Options> Vector3;
40 typedef Eigen::Matrix<Scalar,6,1,Options> Vector6;
41 typedef Eigen::Matrix<Scalar,6,6,Options> Matrix6;
42 typedef typename PINOCCHIO_EIGEN_REF_CONST_TYPE(Vector6) ToVectorConstReturnType;
43 typedef typename PINOCCHIO_EIGEN_REF_TYPE(Vector6) ToVectorReturnType;
44 typedef Vector3 AngularType;
45 typedef Vector3 LinearType;
46 typedef const Vector3 ConstAngularType;
47 typedef const Vector3 ConstLinearType;
48 typedef Matrix6 ActionMatrixType;
57 template<
typename _Scalar,
int _Options>
59 :
MotionBase< MotionSphericalTpl<_Scalar,_Options> >
61 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
67 template<
typename Vector3Like>
72 Vector3 & operator() () {
return m_w; }
73 const Vector3 & operator() ()
const {
return m_w; }
80 template<
typename MotionDerived>
83 other.angular() += m_w;
86 template<
typename Derived>
89 other.linear().setZero();
90 other.angular() = m_w;
100 return m_w == other.m_w;
103 template<
typename MotionDerived>
106 return other.angular() == m_w && other.linear().isZero(0);
109 template<
typename S2,
int O2,
typename D2>
113 v.angular().noalias() = m.rotation() * m_w;
116 v.linear().noalias() = m.translation().cross(v.angular());
119 template<
typename S2,
int O2>
123 se3Action_impl(m,res);
127 template<
typename S2,
int O2,
typename D2>
133 v3_tmp.noalias() = m_w.cross(m.translation());
134 v.linear().noalias() = m.rotation().transpose() * v3_tmp;
137 v.angular().noalias() = m.rotation().transpose() * m_w;
140 template<
typename S2,
int O2>
144 se3ActionInverse_impl(m,res);
148 template<
typename M1,
typename M2>
152 mout.linear().noalias() = v.linear().cross(m_w);
155 mout.angular().noalias() = v.angular().cross(m_w);
158 template<
typename M1>
166 const Vector3 & angular()
const {
return m_w; }
167 Vector3 & angular() {
return m_w; }
174 template<
typename S1,
int O1,
typename MotionDerived>
175 inline typename MotionDerived::MotionPlain
178 return typename MotionDerived::MotionPlain(m2.linear(),m2.angular() + m1.angular());
183 template<
typename _Scalar,
int _Options>
186 typedef _Scalar Scalar;
187 enum { Options = _Options };
193 typedef Eigen::Matrix<Scalar,3,1,Options> JointForce;
194 typedef Eigen::Matrix<Scalar,6,3,Options> DenseBase;
195 typedef DenseBase MatrixReturnType;
196 typedef const DenseBase ConstMatrixReturnType;
199 template<
typename _Scalar,
int _Options>
201 :
public ConstraintBase< ConstraintSphericalTpl<_Scalar,_Options> >
203 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
211 int nv_impl()
const {
return NV; }
213 template<
typename Vector3Like>
214 JointMotion __mult__(
const Eigen::MatrixBase<Vector3Like> & w)
const 216 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like,3);
222 template<
typename Derived>
228 template<
typename MatrixDerived>
230 operator*(
const Eigen::MatrixBase<MatrixDerived> & F)
const 233 return F.derived().template middleRows<3>(Inertia::ANGULAR);
239 DenseBase matrix_impl()
const 242 S.template block <3,3>(LINEAR,0).setZero();
243 S.template block <3,3>(ANGULAR,0).setIdentity();
247 template<
typename S1,
int O1>
248 Eigen::Matrix<S1,6,3,O1> se3Action(
const SE3Tpl<S1,O1> & m)
const 250 Eigen::Matrix<S1,6,3,O1> X_subspace;
251 cross(m.translation(),m.rotation(),X_subspace.template middleRows<3>(LINEAR));
252 X_subspace.template middleRows<3>(ANGULAR) = m.rotation();
257 template<
typename S1,
int O1>
258 Eigen::Matrix<S1,6,3,O1> se3ActionInverse(
const SE3Tpl<S1,O1> & m)
const 260 Eigen::Matrix<S1,6,3,O1> X_subspace;
261 AxisX::cross(m.translation(),X_subspace.template middleRows<3>(ANGULAR).col(0));
262 AxisY::cross(m.translation(),X_subspace.template middleRows<3>(ANGULAR).col(1));
263 AxisZ::cross(m.translation(),X_subspace.template middleRows<3>(ANGULAR).col(2));
265 X_subspace.template middleRows<3>(LINEAR).noalias()
266 = m.rotation().transpose() * X_subspace.template middleRows<3>(ANGULAR);
267 X_subspace.template middleRows<3>(ANGULAR) = m.rotation().transpose();
272 template<
typename MotionDerived>
275 const typename MotionDerived::ConstLinearType v = m.linear();
276 const typename MotionDerived::ConstAngularType w = m.angular();
279 skew(v,res.template middleRows<3>(LINEAR));
280 skew(w,res.template middleRows<3>(ANGULAR));
289 template<
typename MotionDerived,
typename S2,
int O2>
290 inline typename MotionDerived::MotionPlain
294 return m2.motionAction(m1);
298 template<
typename S1,
int O1,
typename S2,
int O2>
299 inline Eigen::Matrix<S2,6,3,O2>
304 typedef typename Inertia::Symmetric3
Symmetric3;
305 Eigen::Matrix<S2,6,3,O2> M;
307 M.template block<3,3>(Inertia::LINEAR,0) =
alphaSkew(-Y.mass(), Y.lever());
308 M.template block<3,3>(Inertia::ANGULAR,0) = (Y.inertia() -
typename Symmetric3::AlphaSkewSquare(Y.mass(), Y.lever())).matrix();
313 template<
typename M6Like,
typename S2,
int O2>
315 operator*(
const Eigen::MatrixBase<M6Like> & Y,
319 return Y.derived().template middleCols<3>(Constraint::ANGULAR);
322 template<
typename S1,
int O1>
324 {
typedef Eigen::Matrix<S1,6,3,O1> ReturnType; };
326 template<
typename S1,
int O1,
typename MotionDerived>
328 {
typedef Eigen::Matrix<S1,6,3,O1> ReturnType; };
332 template<
typename _Scalar,
int _Options>
339 typedef _Scalar Scalar;
340 enum { Options = _Options };
349 typedef Eigen::Matrix<Scalar,6,NV,Options> U_t;
350 typedef Eigen::Matrix<Scalar,NV,NV,Options> D_t;
351 typedef Eigen::Matrix<Scalar,6,NV,Options> UD_t;
353 PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
355 typedef Eigen::Matrix<Scalar,NQ,1,Options> ConfigVector_t;
356 typedef Eigen::Matrix<Scalar,NV,1,Options> TangentVector_t;
359 template<
typename Scalar,
int Options>
363 template<
typename Scalar,
int Options>
367 template<
typename _Scalar,
int _Options>
370 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
373 PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(JointDerived);
374 PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR
387 : M(Transformation_t::Identity())
388 , v(Motion_t::Vector3::Zero())
391 , UDinv(UD_t::Zero())
394 static std::string classname() {
return std::string(
"JointDataSpherical"); }
395 std::string
shortname()
const {
return classname(); }
400 template<
typename _Scalar,
int _Options>
402 :
public JointModelBase< JointModelSphericalTpl<_Scalar,_Options> >
404 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
407 PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(JointDerived);
413 using Base::setIndexes;
415 JointDataDerived
createData()
const {
return JointDataDerived(); }
417 template<
typename ConfigVectorLike>
418 inline void forwardKinematics(Transformation_t & M,
const Eigen::MatrixBase<ConfigVectorLike> & q_joint)
const 420 EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(ConfigVector_t,ConfigVectorLike);
421 typedef typename Eigen::Quaternion<typename ConfigVectorLike::Scalar,PINOCCHIO_EIGEN_PLAIN_TYPE(ConfigVectorLike)::Options> Quaternion;
422 typedef Eigen::Map<const Quaternion> ConstQuaternionMap;
424 ConstQuaternionMap quat(q_joint.derived().data());
426 assert(math::fabs(quat.coeffs().squaredNorm()-1.) <= 1e-4);
428 M.rotation(quat.matrix());
429 M.translation().setZero();
432 template<
typename QuaternionDerived>
433 void calc(JointDataDerived & data,
434 const typename Eigen::QuaternionBase<QuaternionDerived> & quat)
const 436 data.M.rotation(quat.matrix());
439 template<
typename ConfigVector>
441 void calc(JointDataDerived & data,
442 const typename Eigen::PlainObjectBase<ConfigVector> & qs)
const 444 typedef typename Eigen::Quaternion<typename ConfigVector::Scalar,ConfigVector::Options> Quaternion;
445 typedef Eigen::Map<const Quaternion> ConstQuaternionMap;
447 ConstQuaternionMap quat(qs.template segment<NQ>(
idx_q()).data());
451 template<
typename ConfigVector>
453 void calc(JointDataDerived & data,
454 const typename Eigen::MatrixBase<ConfigVector> & qs)
const 456 typedef typename Eigen::Quaternion<Scalar,Options> Quaternion;
458 const Quaternion quat(qs.template segment<NQ>(
idx_q()));
462 template<
typename ConfigVector,
typename TangentVector>
463 void calc(JointDataDerived & data,
464 const typename Eigen::MatrixBase<ConfigVector> & qs,
465 const typename Eigen::MatrixBase<TangentVector> & vs)
const 467 calc(data,qs.derived());
469 data.v.angular() = vs.template segment<NV>(
idx_v());
472 template<
typename Matrix6Like>
473 void calc_aba(JointDataDerived & data,
474 const Eigen::MatrixBase<Matrix6Like> & I,
475 const bool update_I)
const 477 data.U = I.template block<6,3>(0,Inertia::ANGULAR);
482 internal::PerformStYSInversion<Scalar>::run(data.U.template middleRows<3>(Inertia::ANGULAR),data.Dinv);
484 data.UDinv.template middleRows<3>(Inertia::ANGULAR).setIdentity();
485 data.UDinv.template middleRows<3>(Inertia::LINEAR).noalias() = data.U.template block<3,3>(Inertia::LINEAR, 0) * data.Dinv;
489 Matrix6Like & I_ = PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like,I);
490 I_.template block<3,3>(Inertia::LINEAR,Inertia::LINEAR)
491 -= data.UDinv.template middleRows<3>(Inertia::LINEAR) * I_.template block<3,3> (Inertia::ANGULAR, Inertia::LINEAR);
492 I_.template block<6,3>(0,Inertia::ANGULAR).setZero();
493 I_.template block<3,3>(Inertia::ANGULAR,Inertia::LINEAR).setZero();
497 static std::string classname() {
return std::string(
"JointModelSpherical"); }
498 std::string
shortname()
const {
return classname(); }
501 template<
typename NewScalar>
514 #include <boost/type_traits.hpp> 518 template<
typename Scalar,
int Options>
520 :
public integral_constant<bool,true> {};
522 template<
typename Scalar,
int Options>
524 :
public integral_constant<bool,true> {};
526 template<
typename Scalar,
int Options>
528 :
public integral_constant<bool,true> {};
530 template<
typename Scalar,
int Options>
532 :
public integral_constant<bool,true> {};
535 #endif // ifndef __pinocchio_joint_spherical_hpp__
int idx_q(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxQVisitor to get the index in the full model configuration space...
int idx_v(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxVVisitor to get the index in the full model tangent space corre...
Return type of the ation of a Motion onto an object of type D.
JointDataTpl< Scalar, Options, JointCollectionTpl > createData(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through CreateData visitor to create a JointDataTpl.
JointModelSphericalTpl< NewScalar, Options > cast() const
ConstAngularType angular() const
Return the angular part of the force vector.
void forwardKinematics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Update the joint placements according to the current joint configuration.
std::string shortname(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointShortnameVisitor to get the shortname of the derived joint model...
void cross(const Eigen::MatrixBase< Vector3 > &v, const Eigen::MatrixBase< Matrix3xIn > &Min, const Eigen::MatrixBase< Matrix3xOut > &Mout)
Applies the cross product onto the columns of M.
Main pinocchio namespace.
void alphaSkew(const Scalar alpha, const Eigen::MatrixBase< Vector3 > &v, const Eigen::MatrixBase< Matrix3 > &M)
Computes the skew representation of a given 3d vector multiplied by a given scalar. i.e. the antisymmetric matrix representation of the cross product operator ( )
Common traits structure to fully define base classes for CRTP.
void skew(const Eigen::MatrixBase< Vector3 > &v, const Eigen::MatrixBase< Matrix3 > &M)
Computes the skew representation of a given 3d vector, i.e. the antisymmetric matrix representation o...
void calc_aba(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel, JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata, const Eigen::MatrixBase< Matrix6Type > &I, const bool update_I)
Visit a JointModelTpl and the corresponding JointDataTpl through JointCalcAbaVisitor to...
MultiplicationOp< InertiaTpl< Scalar, Options >, ConstraintDerived >::ReturnType operator*(const InertiaTpl< Scalar, Options > &Y, const ConstraintBase< ConstraintDerived > &constraint)
.