10   template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI 
void 
   11   updateGlobalPlacements<context::Scalar, context::Options, JointCollectionDefaultTpl>(
 
   15     template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI 
void forwardKinematics<
 
   18       JointCollectionDefaultTpl,
 
   19       Eigen::Ref<const context::VectorXs>>(
 
   22       const Eigen::MatrixBase<Eigen::Ref<const context::VectorXs>> &);
 
   24     template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI 
void forwardKinematics<
 
   27       JointCollectionDefaultTpl,
 
   28       Eigen::Ref<const context::VectorXs>,
 
   29       Eigen::Ref<const context::VectorXs>>(
 
   32       const Eigen::MatrixBase<Eigen::Ref<const context::VectorXs>> &,
 
   33       const Eigen::MatrixBase<Eigen::Ref<const context::VectorXs>> &);
 
   35     template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI 
void forwardKinematics<
 
   38       JointCollectionDefaultTpl,
 
   39       Eigen::Ref<const context::VectorXs>,
 
   40       Eigen::Ref<const context::VectorXs>,
 
   41       Eigen::Ref<const context::VectorXs>>(
 
   44       const Eigen::MatrixBase<Eigen::Ref<const context::VectorXs>> &,
 
   45       const Eigen::MatrixBase<Eigen::Ref<const context::VectorXs>> &,
 
   46       const Eigen::MatrixBase<Eigen::Ref<const context::VectorXs>> &);
 
   49   template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
 
   50     SE3Tpl<context::Scalar, context::Options>
 
   51     getRelativePlacement<context::Scalar, context::Options, JointCollectionDefaultTpl>(
 
   58   template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
 
   59     MotionTpl<context::Scalar, context::Options>
 
   60     getVelocity<context::Scalar, context::Options, JointCollectionDefaultTpl>(
 
   63   template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
 
   64     MotionTpl<context::Scalar, context::Options>
 
   65     getAcceleration<context::Scalar, context::Options, JointCollectionDefaultTpl>(
 
   68   template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
 
   69     MotionTpl<context::Scalar, context::Options>
 
   70     getClassicalAcceleration<context::Scalar, context::Options, JointCollectionDefaultTpl>(