19 #ifndef __se3_joint_free_flyer_hpp__    20 #define __se3_joint_free_flyer_hpp__    22 #include "pinocchio/macros.hpp"    23 #include "pinocchio/spatial/inertia.hpp"    24 #include "pinocchio/spatial/explog.hpp"    25 #include "pinocchio/multibody/joint/joint-base.hpp"    26 #include "pinocchio/multibody/constraint.hpp"    27 #include "pinocchio/math/fwd.hpp"    28 #include "pinocchio/math/quaternion.hpp"    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,4,1,Options> Vector4;
    42     typedef Eigen::Matrix<Scalar,6,1,Options> Vector6;
    43     typedef Eigen::Matrix<Scalar,3,3,Options> Matrix3;
    44     typedef Eigen::Matrix<Scalar,4,4,Options> Matrix4;
    45     typedef Eigen::Matrix<Scalar,6,6,Options> Matrix6;
    46     typedef Matrix3 Angular_t;
    47     typedef Vector3 Linear_t;
    48     typedef const Matrix3 ConstAngular_t;
    49     typedef const Vector3 ConstLinear_t;
    50     typedef Matrix6 ActionMatrix_t;
    51     typedef Eigen::Quaternion<Scalar,Options> Quaternion_t;
    60     typedef Eigen::Matrix<Scalar,6,1,Options> JointMotion;
    61     typedef Eigen::Matrix<Scalar,6,1,Options> JointForce;
    62     typedef Eigen::Matrix<Scalar,6,6,Options> DenseBase;
    63     typedef const DenseBase ConstMatrixReturnType;
    64     typedef DenseBase MatrixReturnType;
    68   template<
typename _Scalar, 
int _Options>
    72     enum { NV = 6, Options = 0 };
    77     template<
typename S1, 
int O1>
    78     typename SE3::Matrix6 se3Action(
const SE3Tpl<S1,O1> & m)
 const    79     { 
return m.toActionMatrix(); }
    81     int nv_impl()
 const { 
return NV; }
    85       template<
typename Derived>
    91       template<
typename MatrixDerived>
    92       typename EIGEN_REF_CONSTTYPE(MatrixDerived)
    93       operator*(
const Eigen::MatrixBase<MatrixDerived> & F)
   100     DenseBase matrix_impl()
 const { 
return DenseBase::Identity(); }
   102     template<
typename MotionDerived>
   103     typename MotionDerived::ActionMatrixType
   105     { 
return v.toActionMatrix(); }
   109   template<
typename Scalar, 
int Options, 
typename Vector6Like>
   113     EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector6Like,6);
   119   template<
typename S1, 
int O1, 
typename S2, 
int O2>
   127   template<
typename Matrix6Like, 
typename S2, 
int O2>
   128   inline typename EIGEN_REF_CONSTTYPE(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 double 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     typedef Eigen::Matrix<Scalar,NQ,1,Options> ConfigVector_t;
   170     typedef Eigen::Matrix<Scalar,NV,1,Options> TangentVector_t;
   173   template<
typename Scalar, 
int Options>
   177   template<
typename Scalar, 
int Options>
   181   template<
typename _Scalar, 
int _Options>
   185     SE3_JOINT_TYPEDEF_TEMPLATE;
   203   template<
typename _Scalar, 
int _Options>
   207     SE3_JOINT_TYPEDEF_TEMPLATE;
   214     JointDataDerived 
createData()
 const { 
return JointDataDerived(); }
   216     template<
typename ConfigVectorLike>
   217     inline void forwardKinematics(Transformation_t & M, 
const Eigen::MatrixBase<ConfigVectorLike> & q_joint)
 const   219       EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(ConfigVector_t,ConfigVectorLike);
   220       typedef typename Eigen::Quaternion<typename ConfigVectorLike::Scalar,EIGEN_PLAIN_TYPE(ConfigVectorLike)::Options> Quaternion;
   221       typedef Eigen::Map<const Quaternion> ConstQuaternionMap;
   223       ConstQuaternionMap quat(q_joint.template tail<4>().data());
   225       assert(std::fabs(quat.coeffs().squaredNorm()-1.) <= 1e-4);
   227       M.rotation(quat.matrix());
   228       M.translation(q_joint.template head<3>());
   231     template<
typename ConfigVector>
   232     void calc(JointDataDerived & data,
   233               const typename Eigen::MatrixBase<ConfigVector> & qs)
 const   235       EIGEN_STATIC_ASSERT_VECTOR_ONLY(ConfigVector);
   236       typedef typename Eigen::Quaternion<typename ConfigVector::Scalar,ConfigVector::Options> Quaternion;
   237       typedef Eigen::Map<const Quaternion> ConstQuaternionMap;
   239       typename ConfigVector::template ConstFixedSegmentReturnType<NQ>::Type q = qs.template segment<NQ>(
idx_q());
   240       ConstQuaternionMap quat(q.template tail<4>().data());
   242       data.M.rotation(quat.matrix());
   243       data.M.translation(q.template head<3>());
   246     template<
typename ConfigVector, 
typename TangentVector>
   247     void calc(JointDataDerived & data,
   248               const typename Eigen::MatrixBase<ConfigVector> & qs,
   249               const typename Eigen::MatrixBase<TangentVector> & vs)
 const   251       EIGEN_STATIC_ASSERT_VECTOR_ONLY(TangentVector);
   252       calc(data,qs.derived());
   254       data.v = vs.template segment<NV>(
idx_v());
   257     template<
typename S2, 
int O2>
   258     void calc_aba(JointDataDerived & data, Eigen::Matrix<S2,6,6,O2> & I, 
const bool update_I)
 const   261       data.Dinv = I.inverse();
   270       return 2.*sqrt(sqrt(Eigen::NumTraits<Scalar>::epsilon()));
   273     static std::string classname() { 
return std::string(
"JointModelFreeFlyer"); }
   274     std::string 
shortname()
 const { 
return classname(); }
   280 #endif // ifndef __se3_joint_free_flyer_hpp__ 
JointDataVariant createData(const JointModelVariant &jmodel)
Visit a JointModelVariant through CreateData visitor to create a JointDataVariant. 
 
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...
 
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...
 
ToVectorConstReturnType toVector() const 
Return the force as an Eigen vector.