6 #ifndef __pinocchio_joint_free_flyer_hpp__ 7 #define __pinocchio_joint_free_flyer_hpp__ 9 #include "pinocchio/macros.hpp" 10 #include "pinocchio/spatial/inertia.hpp" 11 #include "pinocchio/spatial/explog.hpp" 12 #include "pinocchio/multibody/joint/joint-base.hpp" 13 #include "pinocchio/multibody/constraint.hpp" 14 #include "pinocchio/math/fwd.hpp" 15 #include "pinocchio/math/quaternion.hpp" 22 template<
typename _Scalar,
int _Options>
25 typedef _Scalar Scalar;
26 enum { Options = _Options };
27 typedef Eigen::Matrix<Scalar,3,1,Options> Vector3;
28 typedef Eigen::Matrix<Scalar,4,1,Options> Vector4;
29 typedef Eigen::Matrix<Scalar,6,1,Options> Vector6;
30 typedef Eigen::Matrix<Scalar,3,3,Options> Matrix3;
31 typedef Eigen::Matrix<Scalar,4,4,Options> Matrix4;
32 typedef Eigen::Matrix<Scalar,6,6,Options> Matrix6;
33 typedef Matrix3 Angular_t;
34 typedef Vector3 Linear_t;
35 typedef const Matrix3 ConstAngular_t;
36 typedef const Vector3 ConstLinear_t;
37 typedef Matrix6 ActionMatrix_t;
38 typedef Eigen::Quaternion<Scalar,Options> Quaternion_t;
48 typedef Eigen::Matrix<Scalar,6,1,Options> JointForce;
49 typedef Eigen::Matrix<Scalar,6,6,Options> DenseBase;
50 typedef typename Matrix6::IdentityReturnType ConstMatrixReturnType;
51 typedef typename Matrix6::IdentityReturnType MatrixReturnType;
55 template<
typename _Scalar,
int _Options>
59 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
62 enum { NV = 6, Options = _Options };
68 template<
typename Vector6Like>
69 JointMotion __mult__(
const Eigen::MatrixBase<Vector6Like> & vj)
const 71 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector6Like,6);
72 return JointMotion(vj);
75 template<
typename S1,
int O1>
76 typename SE3::ActionMatrixType se3Action(
const SE3Tpl<S1,O1> & m)
const 77 {
return m.toActionMatrix(); }
79 int nv_impl()
const {
return NV; }
83 template<
typename Derived>
89 template<
typename MatrixDerived>
90 typename PINOCCHIO_EIGEN_REF_CONST_TYPE(MatrixDerived)
91 operator*(
const Eigen::MatrixBase<MatrixDerived> & F)
98 MatrixReturnType matrix_impl()
const {
return DenseBase::Identity(); }
100 template<
typename MotionDerived>
101 typename MotionDerived::ActionMatrixType
103 {
return v.toActionMatrix(); }
107 template<
typename Scalar,
int Options,
typename Vector6Like>
110 const Eigen::MatrixBase<Vector6Like> & v)
112 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector6Like,6);
115 return Motion(v.derived());
119 template<
typename S1,
int O1,
typename S2,
int O2>
127 template<
typename Matrix6Like,
typename S2,
int O2>
128 inline typename PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like)
136 template<
typename S1,
int O1>
137 struct SE3GroupAction< ConstraintIdentityTpl<S1,O1> >
140 template<
typename S1,
int O1,
typename MotionDerived>
141 struct MotionAlgebraAction< ConstraintIdentityTpl<S1,O1>,MotionDerived >
147 template<
typename _Scalar,
int _Options>
154 typedef _Scalar Scalar;
155 enum { Options = _Options };
162 typedef Eigen::Matrix<Scalar,6,NV,Options> F_t;
165 typedef Eigen::Matrix<Scalar,6,NV,Options> U_t;
166 typedef Eigen::Matrix<Scalar,NV,NV,Options> D_t;
167 typedef Eigen::Matrix<Scalar,6,NV,Options> UD_t;
169 PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
171 typedef Eigen::Matrix<Scalar,NQ,1,Options> ConfigVector_t;
172 typedef Eigen::Matrix<Scalar,NV,1,Options> TangentVector_t;
175 template<
typename Scalar,
int Options>
179 template<
typename Scalar,
int Options>
183 template<
typename _Scalar,
int _Options>
186 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
188 PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE;
189 PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR
205 static std::string classname() {
return std::string(
"JointDataFreeFlyer"); }
206 std::string
shortname()
const {
return classname(); }
211 template<
typename _Scalar,
int _Options>
213 :
public JointModelBase< JointModelFreeFlyerTpl<_Scalar,_Options> >
215 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
217 PINOCCHIO_JOINT_TYPEDEF_TEMPLATE;
223 using Base::setIndexes;
225 JointDataDerived
createData()
const {
return JointDataDerived(); }
227 template<
typename ConfigVectorLike>
228 inline void forwardKinematics(Transformation_t & M,
const Eigen::MatrixBase<ConfigVectorLike> & q_joint)
const 230 EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(ConfigVector_t,ConfigVectorLike);
231 typedef typename Eigen::Quaternion<typename ConfigVectorLike::Scalar,PINOCCHIO_EIGEN_PLAIN_TYPE(ConfigVectorLike)::Options> Quaternion;
232 typedef Eigen::Map<const Quaternion> ConstQuaternionMap;
234 ConstQuaternionMap quat(q_joint.template tail<4>().data());
236 assert(math::fabs(quat.coeffs().squaredNorm()-1.) <= 1e-4);
238 M.rotation(quat.matrix());
239 M.translation(q_joint.template head<3>());
242 template<
typename Vector3Derived,
typename QuaternionDerived>
244 void calc(JointDataDerived & data,
245 const typename Eigen::MatrixBase<Vector3Derived> & trans,
246 const typename Eigen::QuaternionBase<QuaternionDerived> & quat)
const 248 data.M.translation(trans);
249 data.M.rotation(quat.matrix());
252 template<
typename ConfigVector>
254 void calc(JointDataDerived & data,
255 const typename Eigen::PlainObjectBase<ConfigVector> & qs)
const 257 typedef typename Eigen::Quaternion<typename ConfigVector::Scalar,ConfigVector::Options> Quaternion;
258 typedef Eigen::Map<const Quaternion> ConstQuaternionMap;
260 typename ConfigVector::template ConstFixedSegmentReturnType<NQ>::Type q = qs.template segment<NQ>(
idx_q());
261 ConstQuaternionMap quat(q.template tail<4>().data());
263 calc(data,q.template head<3>(),quat);
266 template<
typename ConfigVector>
268 void calc(JointDataDerived & data,
269 const typename Eigen::MatrixBase<ConfigVector> & qs)
const 271 typedef typename Eigen::Quaternion<Scalar,Options> Quaternion;
273 typename ConfigVector::template ConstFixedSegmentReturnType<NQ>::Type q = qs.template segment<NQ>(
idx_q());
274 const Quaternion quat(q.template tail<4>());
276 calc(data,q.template head<3>(),quat);
279 template<
typename ConfigVector,
typename TangentVector>
281 void calc(JointDataDerived & data,
282 const typename Eigen::MatrixBase<ConfigVector> & qs,
283 const typename Eigen::MatrixBase<TangentVector> & vs)
const 285 calc(data,qs.derived());
287 data.v = vs.template segment<NV>(
idx_v());
290 template<
typename Matrix6Like>
291 void calc_aba(JointDataDerived & data,
const Eigen::MatrixBase<Matrix6Like> & I,
const bool update_I)
const 294 data.Dinv.setIdentity();
295 I.llt().solveInPlace(data.Dinv);
298 PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like,I).setZero();
304 return 2.*sqrt(sqrt(Eigen::NumTraits<Scalar>::epsilon()));
307 static std::string classname() {
return std::string(
"JointModelFreeFlyer"); }
308 std::string
shortname()
const {
return classname(); }
311 template<
typename NewScalar>
324 #include <boost/type_traits.hpp> 328 template<
typename Scalar,
int Options>
330 :
public integral_constant<bool,true> {};
332 template<
typename Scalar,
int Options>
334 :
public integral_constant<bool,true> {};
336 template<
typename Scalar,
int Options>
338 :
public integral_constant<bool,true> {};
340 template<
typename Scalar,
int Options>
342 :
public integral_constant<bool,true> {};
345 #endif // ifndef __pinocchio_joint_free_flyer_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...
JointModelFreeFlyerTpl< NewScalar, Options > cast() const
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...
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...
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...
ToVectorConstReturnType toVector() const
Return the force as an Eigen 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...