6 #ifndef __pinocchio_multibody_joint_planar_hpp__ 
    7 #define __pinocchio_multibody_joint_planar_hpp__ 
   19   template<
typename Scalar, 
int Options = context::Options>
 
   23   template<
typename Scalar, 
int Options>
 
   29   template<
typename Scalar, 
int Options, 
typename MotionDerived>
 
   35   template<
typename _Scalar, 
int _Options>
 
   43     typedef Eigen::Matrix<Scalar, 3, 1, Options> 
Vector3;
 
   44     typedef Eigen::Matrix<Scalar, 6, 1, Options> 
Vector6;
 
   45     typedef Eigen::Matrix<Scalar, 4, 4, Options> 
Matrix4;
 
   46     typedef Eigen::Matrix<Scalar, 6, 6, Options> 
Matrix6;
 
   64   template<
typename _Scalar, 
int _Options>
 
   65   struct MotionPlanarTpl : MotionBase<MotionPlanarTpl<_Scalar, _Options>>
 
   67     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
   78       m_data << x_dot, y_dot, theta_dot;
 
   81     template<
typename Vector3Like>
 
   85       EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3);
 
   88     inline PlainReturnType 
plain()
 const 
   90       return PlainReturnType(
 
   91         typename PlainReturnType::Vector3(
vx(), 
vy(), 
Scalar(0)),
 
   95     template<
typename Derived>
 
  103     template<
typename MotionDerived>
 
  110     template<
typename S2, 
int O2, 
typename D2>
 
  113       v.angular().noalias() = 
m.rotation().col(2) * 
wz();
 
  114       v.linear().noalias() = 
m.rotation().template leftCols<2>() * 
m_data.template head<2>();
 
  115       v.linear() += 
m.translation().cross(
v.angular());
 
  118     template<
typename S2, 
int O2>
 
  126     template<
typename S2, 
int O2, 
typename D2>
 
  135       v.linear().noalias() = 
m.rotation().transpose() * v3_tmp;
 
  138       v.angular().noalias() = 
m.rotation().transpose().col(2) * 
wz();
 
  141     template<
typename S2, 
int O2>
 
  149     template<
typename M1, 
typename M2>
 
  155       typename M1::ConstAngularType w_in = 
v.angular();
 
  156       typename M2::LinearType v_out = mout.
linear();
 
  158       v_out[0] -= w_in[2] * 
vy();
 
  159       v_out[1] += w_in[2] * 
vx();
 
  160       v_out[2] += -w_in[1] * 
vx() + w_in[0] * 
vy();
 
  166     template<
typename M1>
 
  220   template<
typename Scalar, 
int Options, 
typename MotionDerived>
 
  221   inline typename MotionDerived::MotionPlain
 
  224     typename MotionDerived::MotionPlain result(m2);
 
  225     result.linear()[0] += m1.vx();
 
  226     result.linear()[1] += m1.vy();
 
  228     result.angular()[2] += m1.wz();
 
  233   template<
typename Scalar, 
int Options>
 
  236   template<
typename _Scalar, 
int _Options>
 
  260   template<
typename _Scalar, 
int _Options>
 
  264     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
  274     template<
typename Vector3Like>
 
  275     JointMotion 
__mult__(
const Eigen::MatrixBase<Vector3Like> & vj)
 const 
  277       EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3);
 
  278       return JointMotion(vj);
 
  294       template<
typename Derived>
 
  302       template<
typename Derived>
 
  308         typedef Eigen::Matrix<Scalar, 3, Derived::ColsAtCompileTime> MatrixReturnType;
 
  309         assert(F.rows() == 6);
 
  311         MatrixReturnType result(3, F.cols());
 
  312         result.template topRows<2>() = F.template topRows<2>();
 
  313         result.template bottomRows<1>() = F.template bottomRows<1>();
 
  327       S.template block<3, 3>(Inertia::LINEAR, 0).setZero();
 
  328       S.template block<3, 3>(Inertia::ANGULAR, 0).setZero();
 
  329       S(Inertia::LINEAR + 0, 0) = 
Scalar(1);
 
  330       S(Inertia::LINEAR + 1, 1) = 
Scalar(1);
 
  331       S(Inertia::ANGULAR + 2, 2) = 
Scalar(1);
 
  335     template<
typename S1, 
int O1>
 
  338       DenseBase X_subspace;
 
  341       X_subspace.template block<3, 2>(Motion::LINEAR, 0) = 
m.rotation().template leftCols<2>();
 
  342       X_subspace.template block<3, 1>(Motion::LINEAR, 2).noalias() =
 
  343         m.translation().cross(
m.rotation().template rightCols<1>());
 
  346       X_subspace.template block<3, 2>(Motion::ANGULAR, 0).setZero();
 
  347       X_subspace.template block<3, 1>(Motion::ANGULAR, 2) = 
m.rotation().template rightCols<1>();
 
  352     template<
typename S1, 
int O1>
 
  355       DenseBase X_subspace;
 
  358       X_subspace.template block<3, 2>(Motion::LINEAR, 0) =
 
  359         m.rotation().transpose().template leftCols<2>();
 
  360       X_subspace.template block<3, 1>(Motion::ANGULAR, 2).noalias() =
 
  361         m.rotation().transpose() * 
m.translation(); 
 
  362       X_subspace.template block<3, 1>(Motion::LINEAR, 2).noalias() =
 
  363         -X_subspace.template block<3, 1>(Motion::ANGULAR, 2)
 
  364            .cross(
m.rotation().transpose().template rightCols<1>());
 
  367       X_subspace.template block<3, 2>(Motion::ANGULAR, 0).setZero();
 
  368       X_subspace.template block<3, 1>(Motion::ANGULAR, 2) =
 
  369         m.rotation().transpose().template rightCols<1>();
 
  374     template<
typename MotionDerived>
 
  377       const typename MotionDerived::ConstLinearType 
v = 
m.linear();
 
  378       const typename MotionDerived::ConstAngularType 
w = 
m.angular();
 
  379       DenseBase 
res(DenseBase::Zero());
 
  400   template<
typename MotionDerived, 
typename S2, 
int O2>
 
  401   inline typename MotionDerived::MotionPlain
 
  404     return m2.motionAction(m1);
 
  408   template<
typename S1, 
int O1, 
typename S2, 
int O2>
 
  409   inline typename Eigen::Matrix<S1, 6, 3, O1>
 
  414     typedef Eigen::Matrix<S1, 6, 3, O1> ReturnType;
 
  418     const typename Inertia::Vector3 & 
com = 
Y.lever();
 
  421     M.template topLeftCorner<3, 3>().setZero();
 
  422     M.template topLeftCorner<2, 2>().diagonal().fill(
mass);
 
  424     const typename Inertia::Vector3 mc(
mass * 
com);
 
  425     M.template rightCols<1>().template head<2>() << -mc(1), mc(0);
 
  427     M.template bottomLeftCorner<3, 2>() << (
Scalar)0, -mc(2), mc(2), (
Scalar)0, -mc(1), mc(0);
 
  428     M.template rightCols<1>().template tail<3>() = inertia.data().template tail<3>();
 
  429     M.template rightCols<1>()[3] -= mc(0) * 
com(2);
 
  430     M.template rightCols<1>()[4] -= mc(1) * 
com(2);
 
  439   template<
typename M6Like, 
typename S2, 
int O2>
 
  440   inline Eigen::Matrix<S2, 6, 3, O2>
 
  443     EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(M6Like, 6, 6);
 
  444     typedef Eigen::Matrix<S2, 6, 3, O2> Matrix63;
 
  447     IS.template leftCols<2>() = 
Y.template leftCols<2>();
 
  448     IS.template rightCols<1>() = 
Y.template rightCols<1>();
 
  453   template<
typename S1, 
int O1>
 
  459   template<
typename S1, 
int O1, 
typename MotionDerived>
 
  465   template<
typename Scalar, 
int Options>
 
  468   template<
typename _Scalar, 
int _Options>
 
  490     typedef Eigen::Matrix<Scalar, 6, NV, Options> 
U_t;
 
  491     typedef Eigen::Matrix<Scalar, NV, NV, Options> 
D_t;
 
  492     typedef Eigen::Matrix<Scalar, 6, NV, Options> 
UD_t;
 
  502   template<
typename _Scalar, 
int _Options>
 
  508   template<
typename _Scalar, 
int _Options>
 
  515   template<
typename _Scalar, 
int _Options>
 
  518     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
  539     , 
joint_v(TangentVector_t::Zero())
 
  540     , 
M(Transformation_t::Identity())
 
  541     , 
v(Motion_t::Vector3::Zero())
 
  544     , 
UDinv(UD_t::Zero())
 
  551       return std::string(
"JointDataPlanar");
 
  561   template<
typename _Scalar, 
int _Options>
 
  562   struct JointModelPlanarTpl : 
public JointModelBase<JointModelPlanarTpl<_Scalar, _Options>>
 
  564     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
  577       return JointDataDerived();
 
  582       return {
true, 
true, 
false, 
false};
 
  587       return {
true, 
true, 
false};
 
  590     template<
typename ConfigVector>
 
  594       const Scalar &c_theta = q_joint(2), &s_theta = q_joint(3);
 
  596       M.rotation().template topLeftCorner<2, 2>() << c_theta, -s_theta, s_theta, c_theta;
 
  597       M.translation().template head<2>() = q_joint.template head<2>();
 
  600     template<
typename ConfigVector>
 
  601     void calc(JointDataDerived & 
data, 
const typename Eigen::MatrixBase<ConfigVector> & 
qs)
 const 
  605       const Scalar &c_theta = 
data.joint_q(2), &s_theta = 
data.joint_q(3);
 
  607       data.M.rotation().template topLeftCorner<2, 2>() << c_theta, -s_theta, s_theta, c_theta;
 
  608       data.M.translation().template head<2>() = 
data.joint_q.template head<2>();
 
  611     template<
typename TangentVector>
 
  613     calc(JointDataDerived & 
data, 
const Blank, 
const typename Eigen::MatrixBase<TangentVector> & vs)
 
  616       data.joint_v = vs.template segment<NV>(
idx_v());
 
  618 #define q_dot data.joint_v 
  625     template<
typename ConfigVector, 
typename TangentVector>
 
  627       JointDataDerived & 
data,
 
  628       const typename Eigen::MatrixBase<ConfigVector> & 
qs,
 
  629       const typename Eigen::MatrixBase<TangentVector> & vs)
 const 
  633       data.joint_v = vs.template segment<NV>(
idx_v());
 
  635 #define q_dot data.joint_v 
  642     template<
typename VectorLike, 
typename Matrix6Like>
 
  644       JointDataDerived & 
data,
 
  645       const Eigen::MatrixBase<VectorLike> & armature,
 
  646       const Eigen::MatrixBase<Matrix6Like> & I,
 
  647       const bool update_I)
 const 
  649       data.U.template leftCols<2>() = I.template leftCols<2>();
 
  650       data.U.template rightCols<1>() = I.template rightCols<1>();
 
  652       data.StU.template leftCols<2>() = 
data.U.template topRows<2>().transpose();
 
  653       data.StU.template rightCols<1>() = 
data.U.template bottomRows<1>();
 
  655       data.StU.diagonal() += armature;
 
  666       return std::string(
"JointModelPlanar");
 
  674     template<
typename NewScalar>
 
  685   template<
typename Scalar, 
int Options>
 
  692 #include <boost/type_traits.hpp> 
  696   template<
typename Scalar, 
int Options>
 
  698   : 
public integral_constant<bool, true>
 
  702   template<
typename Scalar, 
int Options>
 
  704   : 
public integral_constant<bool, true>
 
  708   template<
typename Scalar, 
int Options>
 
  710   : 
public integral_constant<bool, true>
 
  714   template<
typename Scalar, 
int Options>
 
  716   : 
public integral_constant<bool, true>
 
  721 #endif // ifndef __pinocchio_multibody_joint_planar_hpp__