19 #ifndef __se3_joint_spherical_hpp__ 20 #define __se3_joint_spherical_hpp__ 22 #include "pinocchio/macros.hpp" 23 #include "pinocchio/multibody/joint/joint-base.hpp" 24 #include "pinocchio/multibody/constraint.hpp" 25 #include "pinocchio/math/sincos.hpp" 26 #include "pinocchio/spatial/inertia.hpp" 27 #include "pinocchio/spatial/skew.hpp" 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 EIGEN_REF_CONSTTYPE(Vector6) ToVectorConstReturnType;
43 typedef typename 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;
56 template<
typename _Scalar,
int _Options>
64 Vector3 & operator() () {
return w; }
65 const Vector3 & operator() ()
const {
return w; }
69 return MotionPlain(MotionPlain::Vector3::Zero(), w);
72 template<
typename MotionDerived>
81 template<
typename S1,
int O1,
typename MotionDerived>
82 inline typename MotionDerived::MotionPlain
85 return typename MotionDerived::MotionPlain(m2.linear(),m2.angular() + m1.w);
90 template<
typename _Scalar,
int _Options>
93 typedef _Scalar Scalar;
94 enum { Options = _Options };
95 typedef Eigen::Matrix<Scalar,3,1,Options> Vector3;
96 typedef Eigen::Matrix<Scalar,4,1,Options> Vector4;
97 typedef Eigen::Matrix<Scalar,6,1,Options> Vector6;
98 typedef Eigen::Matrix<Scalar,3,3,Options> Matrix3;
99 typedef Eigen::Matrix<Scalar,4,4,Options> Matrix4;
100 typedef Eigen::Matrix<Scalar,6,6,Options> Matrix6;
101 typedef Matrix3 Angular_t;
102 typedef Vector3 Linear_t;
103 typedef const Matrix3 ConstAngular_t;
104 typedef const Vector3 ConstLinear_t;
105 typedef Matrix6 ActionMatrix_t;
106 typedef Eigen::Quaternion<Scalar,Options> Quaternion_t;
115 typedef Eigen::Matrix<Scalar,3,1,Options> JointMotion;
116 typedef Eigen::Matrix<Scalar,3,1,Options> JointForce;
117 typedef Eigen::Matrix<Scalar,6,3,Options> DenseBase;
118 typedef DenseBase MatrixReturnType;
119 typedef const DenseBase ConstMatrixReturnType;
122 template<
typename _Scalar,
int _Options>
131 int nv_impl()
const {
return NV; }
135 template<
typename Derived>
141 template<
typename MatrixDerived>
143 operator*(
const Eigen::MatrixBase<MatrixDerived> & F)
const 146 return F.derived().template middleRows<3>(Inertia::ANGULAR);
152 DenseBase matrix_impl()
const 155 S.template block <3,3>(LINEAR,0).setZero();
156 S.template block <3,3>(ANGULAR,0).setIdentity();
160 template<
typename S1,
int O1>
161 Eigen::Matrix<S1,6,3,O1> se3Action(
const SE3Tpl<S1,O1> & m)
const 163 Eigen::Matrix<S1,6,3,O1> X_subspace;
164 cross(m.translation(),m.rotation(),X_subspace.template block<3,3>(LINEAR,0));
165 X_subspace.template block<3,3>(ANGULAR,0) = m.rotation();
170 template<
typename MotionDerived>
173 const typename MotionDerived::ConstLinearType v = m.linear();
174 const typename MotionDerived::ConstAngularType w = m.angular();
177 skew(v,res.template middleRows<3>(LINEAR));
178 skew(w,res.template middleRows<3>(ANGULAR));
186 template<
typename Scalar,
int Options,
typename Vector3Like>
189 const Eigen::MatrixBase<Vector3Like>& v)
191 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like,3);
195 template<
typename MotionDerived,
typename S2,
int O2>
196 inline typename MotionDerived::MotionPlain
200 return typename MotionDerived::MotionPlain(m1.template linear().
cross(m2.w),
201 m1.template angular().
cross(m2.w));
205 template<
typename S1,
int O1,
typename S2,
int O2>
206 inline Eigen::Matrix<S2,6,3,O2>
211 Eigen::Matrix<S2,6,3,O2> M;
213 M.template block<3,3>(Inertia::LINEAR,0) =
alphaSkew(-Y.mass(), Y.lever());
214 M.template block<3,3>(Inertia::ANGULAR,0) = (Y.inertia() - Symmetric3::AlphaSkewSquare(Y.mass(), Y.lever())).matrix();
219 template<
typename M6Like,
typename S2,
int O2>
221 operator*(
const Eigen::MatrixBase<M6Like> & Y,
225 return Y.derived().template middleCols<3>(Constraint::ANGULAR);
230 template<
typename S1,
int O1>
231 struct SE3GroupAction< ConstraintSphericalTpl<S1,O1> >
232 {
typedef Eigen::Matrix<S1,6,3,O1> ReturnType; };
234 template<
typename S1,
int O1,
typename MotionDerived>
235 struct MotionAlgebraAction< ConstraintSphericalTpl<S1,O1>,MotionDerived >
236 {
typedef Eigen::Matrix<S1,6,3,O1> ReturnType; };
241 template<
typename _Scalar,
int _Options>
248 typedef _Scalar Scalar;
249 enum { Options = _Options };
256 typedef Eigen::Matrix<Scalar,6,NV,Options> F_t;
259 typedef Eigen::Matrix<Scalar,6,NV,Options> U_t;
260 typedef Eigen::Matrix<Scalar,NV,NV,Options> D_t;
261 typedef Eigen::Matrix<Scalar,6,NV,Options> UD_t;
263 typedef Eigen::Matrix<Scalar,NQ,1,Options> ConfigVector_t;
264 typedef Eigen::Matrix<Scalar,NV,1,Options> TangentVector_t;
267 template<
typename Scalar,
int Options>
271 template<
typename Scalar,
int Options>
275 template<
typename _Scalar,
int _Options>
279 SE3_JOINT_TYPEDEF_TEMPLATE;
297 template<
typename _Scalar,
int _Options>
301 SE3_JOINT_TYPEDEF_TEMPLATE;
308 JointDataDerived
createData()
const {
return JointDataDerived(); }
310 template<
typename ConfigVectorLike>
311 inline void forwardKinematics(Transformation_t & M,
const Eigen::MatrixBase<ConfigVectorLike> & q_joint)
const 313 EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(ConfigVector_t,ConfigVectorLike);
314 typedef typename Eigen::Quaternion<typename ConfigVectorLike::Scalar,EIGEN_PLAIN_TYPE(ConfigVectorLike)::Options> Quaternion;
315 typedef Eigen::Map<const Quaternion> ConstQuaternionMap;
317 ConstQuaternionMap quat(q_joint.derived().data());
319 assert(std::fabs(quat.coeffs().squaredNorm()-1.) <= 1e-4);
321 M.rotation(quat.matrix());
322 M.translation().setZero();
325 template<
typename ConfigVector>
326 void calc(JointDataDerived & data,
327 const typename Eigen::MatrixBase<ConfigVector> & qs)
const 329 EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(ConfigVector_t,ConfigVector);
330 typedef typename Eigen::Quaternion<typename ConfigVector::Scalar,ConfigVector::Options> Quaternion;
331 typedef Eigen::Map<const Quaternion> ConstQuaternionMap;
333 typename ConfigVector::template ConstFixedSegmentReturnType<NQ>::Type & q = qs.template segment<NQ>(
idx_q());
335 ConstQuaternionMap quat(q.data());
336 data.M.rotation(quat.matrix());
339 template<
typename ConfigVector,
typename TangentVector>
340 void calc(JointDataDerived & data,
341 const typename Eigen::MatrixBase<ConfigVector> & qs,
342 const typename Eigen::MatrixBase<TangentVector> & vs)
const 344 EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(TangentVector_t,TangentVector);
345 calc(data,qs.derived());
347 data.v() = vs.template segment<NV>(
idx_v());
350 template<
typename S2,
int O2>
351 void calc_aba(JointDataDerived & data, Eigen::Matrix<S2,6,6,O2> & I,
const bool update_I)
const 353 data.U = I.template block<6,3>(0,Inertia::ANGULAR);
354 data.Dinv = I.template block<3,3>(Inertia::ANGULAR,Inertia::ANGULAR).inverse();
355 data.UDinv.template middleRows<3>(Inertia::ANGULAR).setIdentity();
356 data.UDinv.template middleRows<3>(Inertia::LINEAR) = data.U.template block<3,3>(Inertia::LINEAR, 0) * data.Dinv;
360 I.template block<3,3>(Inertia::LINEAR,Inertia::LINEAR)
361 -= data.UDinv.template middleRows<3>(Inertia::LINEAR) * I.template block<3,3> (Inertia::ANGULAR, Inertia::LINEAR);
362 I.template block<6,3>(0,Inertia::ANGULAR).setZero();
363 I.template block<3,3>(Inertia::ANGULAR,Inertia::LINEAR).setZero();
370 return 2.*sqrt(sqrt(Eigen::NumTraits<Scalar>::epsilon()));
373 static std::string classname() {
return std::string(
"JointModelSpherical"); }
374 std::string
shortname()
const {
return classname(); }
380 #endif // ifndef __se3_joint_spherical_hpp__
JointDataVariant createData(const JointModelVariant &jmodel)
Visit a JointModelVariant through CreateData visitor to create a JointDataVariant.
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 ( )
ConstAngularType angular() const
Return the angular part of the force vector.
void calc_aba(const JointModelVariant &jmodel, JointDataVariant &jdata, Inertia::Matrix6 &I, const bool update_I)
Visit a JointDataVariant and the corresponding JointModelVariant through JointCalcAbaVisitor to...
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...
std::string shortname(const JointModelVariant &jmodel)
Visit a JointModelVariant through JointShortnameVisitor to get the shortname of the derived joint mod...
int idx_q(const JointModelVariant &jmodel)
Visit a JointModelVariant through JointIdxQVisitor to get the index in the full model configuration s...
Eigen::VectorXd finiteDifferenceIncrement(const Model &model)
Computes the finite difference increments for each degree of freedom according to the current joint c...
void forwardKinematics(const Model &model, Data &data, const Eigen::VectorXd &q)
Update the joint placements according to the current joint configuration.
int idx_v(const JointModelVariant &jmodel)
Visit a JointModelVariant through JointIdxVVisitor to get the index in the full model tangent space c...
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.