6 #ifndef __pinocchio_joint_revolute_unaligned_hpp__ 7 #define __pinocchio_joint_revolute_unaligned_hpp__ 9 #include "pinocchio/fwd.hpp" 10 #include "pinocchio/multibody/joint/joint-base.hpp" 11 #include "pinocchio/multibody/constraint.hpp" 12 #include "pinocchio/spatial/inertia.hpp" 22 template<
typename Scalar,
int Options>
28 template<
typename Scalar,
int Options,
typename MotionDerived>
35 template<
typename _Scalar,
int _Options>
38 typedef _Scalar Scalar;
39 enum { Options = _Options };
40 typedef Eigen::Matrix<Scalar,3,1,Options> Vector3;
41 typedef Eigen::Matrix<Scalar,6,1,Options> Vector6;
42 typedef Eigen::Matrix<Scalar,6,6,Options> Matrix6;
43 typedef typename PINOCCHIO_EIGEN_REF_CONST_TYPE(Vector6) ToVectorConstReturnType;
44 typedef typename PINOCCHIO_EIGEN_REF_TYPE(Vector6) ToVectorReturnType;
45 typedef Vector3 AngularType;
46 typedef Vector3 LinearType;
47 typedef const Vector3 ConstAngularType;
48 typedef const Vector3 ConstLinearType;
49 typedef Matrix6 ActionMatrixType;
57 template<
typename _Scalar,
int _Options>
60 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
65 template<
typename Vector3Like,
typename OtherScalar>
67 const OtherScalar & w)
78 template<
typename MotionDerived>
81 v.angular() += axis*w;
84 template<
typename Derived>
87 other.linear().setZero();
88 other.angular().noalias() = axis*w;
91 template<
typename S2,
int O2,
typename D2>
95 v.angular().noalias() = w * m.rotation() * axis;
98 v.linear().noalias() = m.translation().cross(v.angular());
101 template<
typename S2,
int O2>
105 se3Action_impl(m,res);
109 template<
typename S2,
int O2,
typename D2>
115 v3_tmp.noalias() = axis.cross(m.translation());
117 v.linear().noalias() = m.rotation().transpose() * v3_tmp;
120 v.angular().noalias() = m.rotation().transpose() * axis;
124 template<
typename S2,
int O2>
128 se3ActionInverse_impl(m,res);
132 template<
typename M1,
typename M2>
136 mout.linear().noalias() = v.linear().cross(axis);
140 mout.angular().noalias() = v.angular().cross(axis);
144 template<
typename M1>
158 template<
typename S1,
int O1,
typename MotionDerived>
159 inline typename MotionDerived::MotionPlain
162 typename MotionDerived::MotionPlain res(m2);
169 template<
typename _Scalar,
int _Options>
172 typedef _Scalar Scalar;
173 enum { Options = _Options };
174 typedef Eigen::Matrix<Scalar,3,1,Options> Vector3;
175 typedef Eigen::Matrix<Scalar,4,1,Options> Vector4;
176 typedef Eigen::Matrix<Scalar,6,1,Options> Vector6;
177 typedef Eigen::Matrix<Scalar,3,3,Options> Matrix3;
178 typedef Eigen::Matrix<Scalar,4,4,Options> Matrix4;
179 typedef Eigen::Matrix<Scalar,6,6,Options> Matrix6;
180 typedef Matrix3 Angular_t;
181 typedef Vector3 Linear_t;
182 typedef const Matrix3 ConstAngular_t;
183 typedef const Vector3 ConstLinear_t;
184 typedef Matrix6 ActionMatrix_t;
185 typedef Eigen::Quaternion<Scalar,Options> Quaternion_t;
195 typedef Eigen::Matrix<Scalar,1,1,Options> JointForce;
196 typedef Eigen::Matrix<Scalar,6,1,Options> DenseBase;
197 typedef DenseBase MatrixReturnType;
198 typedef const DenseBase ConstMatrixReturnType;
201 template<
typename _Scalar,
int _Options>
203 :
ConstraintBase< ConstraintRevoluteUnalignedTpl<_Scalar,_Options> >
205 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
207 enum { NV = 1, Options = _Options };
215 template<
typename Vector3Like>
220 template<
typename Vector1Like>
221 JointMotion __mult__(
const Eigen::MatrixBase<Vector1Like> & v)
const 223 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector1Like,1);
224 return JointMotion(axis,v[0]);
227 template<
typename S1,
int O1>
228 Eigen::Matrix<Scalar,6,1,Options> se3Action(
const SE3Tpl<S1,O1> & m)
const 231 Eigen::Matrix<Scalar,6,1,Options> res;
232 res.template segment<3>(ANGULAR).noalias() = m.rotation() * axis;
233 res.template segment<3>(LINEAR).noalias() = m.translation().cross(res.template segment<3>(ANGULAR));
237 int nv_impl()
const {
return NV; }
244 template<
typename Derived>
250 typedef Eigen::Matrix<
254 ReturnType res; res[0] = ref.axis.dot(f.
angular());
260 #if EIGEN_VERSION_AT_LEAST(3,2,90) 261 const Eigen::Product<
262 Eigen::Transpose<const Vector3>,
263 typename Eigen::MatrixBase<const D>::template NRowsBlockXpr<3>::Type
266 const typename Eigen::ProductReturnType<
267 Eigen::Transpose<const Vector3>,
268 typename Eigen::MatrixBase<const D>::template NRowsBlockXpr<3>::Type
271 operator*(
const Eigen::MatrixBase<D> & F)
273 EIGEN_STATIC_ASSERT(D::RowsAtCompileTime==6,THIS_METHOD_IS_ONLY_FOR_MATRICES_OF_A_SPECIFIC_SIZE)
275 return ref.axis.transpose() * F.template middleRows<3>(ANGULAR);
288 DenseBase matrix_impl()
const 291 S << Vector3::Zero(), axis;
295 template<
typename MotionDerived>
298 const typename MotionDerived::ConstLinearType v = m.linear();
299 const typename MotionDerived::ConstAngularType w = m.angular();
302 res << v.cross(axis), w.cross(axis);
312 template<
typename MotionDerived,
typename S2,
int O2>
313 inline typename MotionDerived::MotionPlain
317 return m2.motionAction(m1);
321 template<
typename S1,
int O1,
typename S2,
int O2>
322 inline Eigen::Matrix<S2,6,1,O2>
327 const typename Inertia::Scalar & m = Y.mass();
328 const typename Inertia::Vector3 & c = Y.lever();
329 const typename Inertia::Symmetric3 & I = Y.inertia();
331 Eigen::Matrix<S2,6,1,O2>res;
332 res.template segment<3>(Inertia::LINEAR) = -m*c.cross(cru.axis);
333 res.template segment<3>(Inertia::ANGULAR).noalias() = I*cru.axis;
334 res.template segment<3>(Inertia::ANGULAR) += c.cross(res.template segment<3>(Inertia::LINEAR));
340 template<
typename M6Like,
typename S2,
int O2>
342 #if EIGEN_VERSION_AT_LEAST(3,2,90) 343 const typename Eigen::Product<
344 typename Eigen::internal::remove_const<typename SizeDepType<3>::ColsReturn<M6Like>::ConstType>::type,
348 const typename Eigen::ProductReturnType<
349 typename Eigen::internal::remove_const<typename SizeDepType<3>::ColsReturn<M6Like>::ConstType>::type,
356 return Y.derived().template middleCols<3>(Constraint::ANGULAR) * cru.axis;
361 template<
typename Scalar,
int Options>
362 struct SE3GroupAction< ConstraintRevoluteUnalignedTpl<Scalar,Options> >
363 {
typedef Eigen::Matrix<Scalar,6,1,Options> ReturnType; };
365 template<
typename Scalar,
int Options,
typename MotionDerived>
366 struct MotionAlgebraAction< ConstraintRevoluteUnalignedTpl<Scalar,Options>,MotionDerived >
367 {
typedef Eigen::Matrix<Scalar,6,1,Options> ReturnType; };
372 template<
typename _Scalar,
int _Options>
379 typedef _Scalar Scalar;
380 enum { Options = _Options };
387 typedef Eigen::Matrix<Scalar,6,NV,Options> F_t;
390 typedef Eigen::Matrix<Scalar,6,NV,Options> U_t;
391 typedef Eigen::Matrix<Scalar,NV,NV,Options> D_t;
392 typedef Eigen::Matrix<Scalar,6,NV,Options> UD_t;
394 PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
396 typedef Eigen::Matrix<Scalar,NQ,1,Options> ConfigVector_t;
397 typedef Eigen::Matrix<Scalar,NV,1,Options> TangentVector_t;
401 template<
typename Scalar,
int Options>
405 template<
typename Scalar,
int Options>
409 template<
typename _Scalar,
int _Options>
411 :
public JointDataBase< JointDataRevoluteUnalignedTpl<_Scalar,_Options> >
413 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
415 PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE;
416 PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR
432 template<
typename Vector3Like>
436 , v(axis,(Scalar)NAN)
437 , U(), Dinv(), UDinv()
440 static std::string classname() {
return std::string(
"JointDataRevoluteUnaligned"); }
441 std::string
shortname()
const {
return classname(); }
446 template<
typename _Scalar,
int _Options>
448 :
public JointModelBase< JointModelRevoluteUnalignedTpl<_Scalar,_Options> >
450 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
452 PINOCCHIO_JOINT_TYPEDEF_TEMPLATE;
453 typedef Eigen::Matrix<Scalar,3,1,_Options> Vector3;
459 using Base::setIndexes;
467 assert(axis.isUnitary() &&
"Rotation axis is not unitary");
470 template<
typename Vector3Like>
474 EIGEN_STATIC_ASSERT_VECTOR_ONLY(Vector3Like);
475 assert(axis.isUnitary() &&
"Rotation axis is not unitary");
478 JointDataDerived
createData()
const {
return JointDataDerived(axis); }
481 bool isEqual(
const JointModelRevoluteUnalignedTpl & other)
const 483 return Base::isEqual(other) && axis == other.
axis;
486 template<
typename ConfigVector>
487 void calc(JointDataDerived & data,
488 const typename Eigen::MatrixBase<ConfigVector> & qs)
const 490 typedef typename ConfigVector::Scalar OtherScalar;
491 typedef Eigen::AngleAxis<Scalar> AngleAxis;
493 const OtherScalar & q = qs[
idx_q()];
495 data.M.rotation(AngleAxis(q,axis).toRotationMatrix());
498 template<
typename ConfigVector,
typename TangentVector>
499 void calc(JointDataDerived & data,
500 const typename Eigen::MatrixBase<ConfigVector> & qs,
501 const typename Eigen::MatrixBase<TangentVector> & vs)
const 503 calc(data,qs.derived());
505 data.v.w = (Scalar)vs[
idx_v()];
508 template<
typename Matrix6Like>
509 void calc_aba(JointDataDerived & data,
const Eigen::MatrixBase<Matrix6Like> & I,
const bool update_I)
const 511 data.U.noalias() = I.template middleCols<3>(Motion::ANGULAR) * axis;
512 data.Dinv[0] = (Scalar)(1)/axis.dot(data.U.template segment<3>(Motion::ANGULAR));
513 data.UDinv.noalias() = data.U * data.Dinv;
516 PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like,I) -= data.UDinv * data.U.transpose();
522 return 2.*sqrt(sqrt(Eigen::NumTraits<Scalar>::epsilon()));
525 static std::string classname() {
return std::string(
"JointModelRevoluteUnaligned"); }
526 std::string
shortname()
const {
return classname(); }
529 template<
typename NewScalar>
533 ReturnType res(axis.template cast<NewScalar>());
548 #include <boost/type_traits.hpp> 552 template<
typename Scalar,
int Options>
554 :
public integral_constant<bool,true> {};
556 template<
typename Scalar,
int Options>
558 :
public integral_constant<bool,true> {};
560 template<
typename Scalar,
int Options>
562 :
public integral_constant<bool,true> {};
564 template<
typename Scalar,
int Options>
566 :
public integral_constant<bool,true> {};
570 #endif // ifndef __pinocchio_joint_revolute_unaligned_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...
Vector3 axis
3d main axis of the joint.
JointDataTpl< Scalar, Options, JointCollectionTpl > createData(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through CreateData visitor to create a JointDataTpl.
ModelTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType finiteDifferenceIncrement(const ModelTpl< Scalar, Options, JointCollectionTpl > &model)
Computes the finite difference increments for each degree of freedom according to the current joint c...
std::string shortname(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointShortnameVisitor to get the shortname of the derived joint model...
JointModelRevoluteUnalignedTpl< NewScalar, Options > cast() const
ConstAngularType angular() const
Return the angular part of the force vector.
Main pinocchio namespace.
Common traits structure to fully define base classes for CRTP.
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...