6 #ifndef __pinocchio_joint_planar_hpp__ 7 #define __pinocchio_joint_planar_hpp__ 9 #include "pinocchio/macros.hpp" 10 #include "pinocchio/multibody/joint/joint-base.hpp" 11 #include "pinocchio/spatial/cartesian-axis.hpp" 12 #include "pinocchio/multibody/constraint.hpp" 13 #include "pinocchio/spatial/motion.hpp" 14 #include "pinocchio/spatial/inertia.hpp" 24 template<
typename Scalar,
int Options>
30 template<
typename Scalar,
int Options,
typename MotionDerived>
31 struct MotionAlgebraAction<
MotionPlanarTpl<Scalar,Options>, MotionDerived>
37 template<
typename _Scalar,
int _Options>
40 typedef _Scalar Scalar;
41 enum { Options = _Options };
42 typedef Eigen::Matrix<Scalar,3,1,Options> Vector3;
43 typedef Eigen::Matrix<Scalar,6,1,Options> Vector6;
44 typedef Eigen::Matrix<Scalar,6,6,Options> Matrix6;
45 typedef typename PINOCCHIO_EIGEN_REF_CONST_TYPE(Vector6) ToVectorConstReturnType;
46 typedef typename PINOCCHIO_EIGEN_REF_TYPE(Vector6) ToVectorReturnType;
47 typedef Vector3 AngularType;
48 typedef Vector3 LinearType;
49 typedef const Vector3 ConstAngularType;
50 typedef const Vector3 ConstLinearType;
51 typedef Matrix6 ActionMatrixType;
59 template<
typename _Scalar,
int _Options>
62 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
70 const Scalar & theta_dot)
71 : m_x_dot(x_dot), m_y_dot(y_dot), m_theta_dot(theta_dot)
74 template<
typename Vector3Like>
76 : m_x_dot(vj[0]), m_y_dot(vj[1]), m_theta_dot(vj[2])
78 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like,3);
87 template<
typename Derived>
90 other.linear()[0] += m_x_dot;
91 other.linear()[1] += m_y_dot;
92 other.angular()[2] += m_theta_dot;
95 template<
typename MotionDerived>
98 other.linear() << m_x_dot, m_y_dot, (Scalar)0;
99 other.angular() << (Scalar)0, (Scalar)0, m_theta_dot;
102 template<
typename S2,
int O2,
typename D2>
105 v.angular().noalias() = m.rotation().col(2) * m_theta_dot;
106 v.linear().noalias() = m.translation().cross(v.angular());
107 v.linear() += m.rotation().col(0) * m_x_dot;
108 v.linear() += m.rotation().col(1) * m_y_dot;
111 template<
typename S2,
int O2>
115 se3Action_impl(m,res);
119 template<
typename S2,
int O2,
typename D2>
125 AxisZ::alphaCross(m_theta_dot,m.translation(),v3_tmp);
126 v3_tmp[0] += m_x_dot; v3_tmp[1] += m_y_dot;
127 v.linear().noalias() = m.rotation().transpose() * v3_tmp;
130 v.angular().noalias() = m.rotation().transpose().col(2) * m_theta_dot;
133 template<
typename S2,
int O2>
137 se3ActionInverse_impl(m,res);
141 template<
typename M1,
typename M2>
145 AxisZ::alphaCross(-m_theta_dot,v.linear(),mout.linear());
147 typename M1::ConstAngularType w_in = v.angular();
148 typename M2::LinearType v_out = mout.linear();
150 v_out[0] -= w_in[2] * m_y_dot;
151 v_out[1] += w_in[2] * m_x_dot;
152 v_out[2] += -w_in[1] * m_x_dot + w_in[0] * m_y_dot ;
155 AxisZ::alphaCross(-m_theta_dot,v.angular(),mout.angular());
158 template<
typename M1>
173 template<
typename Scalar,
int Options,
typename MotionDerived>
174 inline typename MotionDerived::MotionPlain
177 typename MotionDerived::MotionPlain result(m2);
178 result.linear()[0] += m1.m_x_dot;
179 result.linear()[1] += m1.m_y_dot;
181 result.angular()[2] += m1.m_theta_dot;
188 template<
typename _Scalar,
int _Options>
191 typedef _Scalar Scalar;
192 enum { Options = _Options };
193 typedef Eigen::Matrix<Scalar,3,1,Options> Vector3;
194 typedef Eigen::Matrix<Scalar,4,1,Options> Vector4;
195 typedef Eigen::Matrix<Scalar,6,1,Options> Vector6;
196 typedef Eigen::Matrix<Scalar,3,3,Options> Matrix3;
197 typedef Eigen::Matrix<Scalar,4,4,Options> Matrix4;
198 typedef Eigen::Matrix<Scalar,6,6,Options> Matrix6;
199 typedef Matrix3 Angular_t;
200 typedef Vector3 Linear_t;
201 typedef const Matrix3 ConstAngular_t;
202 typedef const Vector3 ConstLinear_t;
203 typedef Matrix6 ActionMatrix_t;
204 typedef Eigen::Quaternion<Scalar,Options> Quaternion_t;
214 typedef Eigen::Matrix<Scalar,3,1,Options> JointForce;
215 typedef Eigen::Matrix<Scalar,6,3,Options> DenseBase;
216 typedef DenseBase MatrixReturnType;
217 typedef const DenseBase ConstMatrixReturnType;
220 template<
typename _Scalar,
int _Options>
223 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
226 enum { NV = 3, Options = _Options };
231 template<
typename Vector3Like>
232 JointMotion __mult__(
const Eigen::MatrixBase<Vector3Like> & vj)
const 234 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like,3);
235 return JointMotion(vj);
238 int nv_impl()
const {
return NV; }
245 template<
typename Derived>
253 template<
typename Derived>
254 friend typename Eigen::Matrix <typename Eigen::MatrixBase<Derived>::Scalar, 3, Derived::ColsAtCompileTime>
257 typedef typename Eigen::MatrixBase<Derived>::Scalar Scalar;
258 typedef Eigen::Matrix<Scalar, 3, Derived::ColsAtCompileTime> MatrixReturnType;
261 MatrixReturnType result(3, F.cols ());
262 result.template topRows<2>() = F.template topRows<2>();
263 result.template bottomRows<1>() = F.template bottomRows<1>();
271 DenseBase matrix_impl()
const 274 S.template block<3,3>(Inertia::LINEAR, 0).setZero ();
275 S.template block<3,3>(Inertia::ANGULAR, 0).setZero ();
276 S(Inertia::LINEAR + 0,0) = Scalar(1);
277 S(Inertia::LINEAR + 1,1) = Scalar(1);
278 S(Inertia::ANGULAR + 2,2) = Scalar(1);
282 template<
typename S1,
int O1>
285 DenseBase X_subspace;
286 X_subspace.template block <3,2>(Motion::LINEAR, 0) = m.rotation ().template leftCols <2> ();
287 X_subspace.template block <3,1>(Motion::LINEAR, 2) = m.translation().cross(m.rotation ().template rightCols<1>());
289 X_subspace.template block <3,2>(Motion::ANGULAR, 0).setZero ();
290 X_subspace.template block <3,1>(Motion::ANGULAR, 2) = m.rotation ().template rightCols<1>();
295 template<
typename MotionDerived>
298 const typename MotionDerived::ConstLinearType v = m.linear();
299 const typename MotionDerived::ConstAngularType w = m.angular();
300 DenseBase res(DenseBase::Zero());
302 res(0,1) = -w[2]; res(0,2) = v[1];
303 res(1,0) = w[2]; res(1,2) = -v[0];
304 res(2,0) = -w[1]; res(2,1) = w[0];
312 template<
typename MotionDerived,
typename S2,
int O2>
313 inline typename MotionDerived::MotionPlain
316 return m2.motionAction(m1);
320 template<
typename S1,
int O1,
typename S2,
int O2>
321 inline typename Eigen::Matrix<S1,6,3,O1>
325 typedef typename Inertia::Scalar Scalar;
326 typedef Eigen::Matrix<S1,6,3,O1> ReturnType;
329 const Scalar mass = Y.mass();
330 const typename Inertia::Vector3 & com = Y.lever();
331 const typename Inertia::Symmetric3 & inertia = Y.inertia();
333 M.template topLeftCorner<3,3>().setZero();
334 M.template topLeftCorner<2,2>().diagonal().fill(mass);
336 const typename Inertia::Vector3 mc(mass * com);
337 M.template rightCols<1>().
template head<2>() << -mc(1), mc(0);
339 M.template bottomLeftCorner<3,2>() << (Scalar)0, -mc(2), mc(2), (Scalar)0, -mc(1), mc(0);
340 M.template rightCols<1>().
template tail<3>() = inertia.data().template tail<3>();
341 M.template rightCols<1>()[3] -= mc(0)*com(2);
342 M.template rightCols<1>()[4] -= mc(1)*com(2);
343 M.template rightCols<1>()[5] += mass*(com(0)*com(0) + com(1)*com(1));
351 template<
typename M6Like,
typename S2,
int O2>
352 inline Eigen::Matrix<S2,6,3,O2>
353 operator*(
const Eigen::MatrixBase<M6Like> & Y,
356 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(M6Like,6,6);
357 typedef Eigen::Matrix<S2,6,3,O2> Matrix63;
360 IS.template leftCols<2>() = Y.template leftCols<2>();
361 IS.template rightCols<1>() = Y.template rightCols<1>();
368 template<
typename S1,
int O1>
369 struct SE3GroupAction< ConstraintPlanarTpl<S1,O1> >
370 {
typedef Eigen::Matrix<S1,6,3,O1> ReturnType; };
372 template<
typename S1,
int O1,
typename MotionDerived>
373 struct MotionAlgebraAction< ConstraintPlanarTpl<S1,O1>,MotionDerived >
374 {
typedef Eigen::Matrix<S1,6,3,O1> ReturnType; };
379 template<
typename _Scalar,
int _Options>
386 enum { Options = _Options };
387 typedef _Scalar Scalar;
394 typedef Eigen::Matrix<Scalar,6,NV,Options> F_t;
397 typedef Eigen::Matrix<Scalar,6,NV,Options> U_t;
398 typedef Eigen::Matrix<Scalar,NV,NV,Options> D_t;
399 typedef Eigen::Matrix<Scalar,6,NV,Options> UD_t;
401 PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
403 typedef Eigen::Matrix<Scalar,NQ,1,Options> ConfigVector_t;
404 typedef Eigen::Matrix<Scalar,NV,1,Options> TangentVector_t;
407 template<
typename Scalar,
int Options>
409 template<
typename Scalar,
int Options>
412 template<
typename _Scalar,
int _Options>
415 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
417 PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE;
418 PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR
436 static std::string classname() {
return std::string(
"JointDataPlanar"); }
437 std::string
shortname()
const {
return classname(); }
442 template<
typename _Scalar,
int _Options>
446 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
448 PINOCCHIO_JOINT_TYPEDEF_TEMPLATE;
454 using Base::setIndexes;
456 JointDataDerived
createData()
const {
return JointDataDerived(); }
458 template<
typename ConfigVector>
459 inline void forwardKinematics(Transformation_t & M,
const Eigen::MatrixBase<ConfigVector> & q_joint)
const 462 & c_theta = q_joint(2),
463 & s_theta = q_joint(3);
465 M.rotation().template topLeftCorner<2,2>() << c_theta, -s_theta, s_theta, c_theta;
466 M.translation().template head<2>() = q_joint.template head<2>();
469 template<
typename ConfigVector>
470 void calc(JointDataDerived & data,
471 const typename Eigen::MatrixBase<ConfigVector> & qs)
const 473 typedef typename ConfigVector::Scalar Scalar;
474 typename ConfigVector::template ConstFixedSegmentReturnType<NQ>::Type & q = qs.template segment<NQ>(
idx_q());
480 data.M.rotation().template topLeftCorner<2,2>() << c_theta, -s_theta, s_theta, c_theta;
481 data.M.translation().template head<2>() = q.template head<2>();
485 template<
typename ConfigVector,
typename TangentVector>
486 void calc(JointDataDerived & data,
487 const typename Eigen::MatrixBase<ConfigVector> & qs,
488 const typename Eigen::MatrixBase<TangentVector> & vs)
const 490 calc(data,qs.derived());
492 typename TangentVector::template ConstFixedSegmentReturnType<NV>::Type & q_dot = vs.template segment<NV>(
idx_v ());
494 data.v.m_x_dot = q_dot(0);
495 data.v.m_y_dot = q_dot(1);
496 data.v.m_theta_dot = q_dot(2);
499 template<
typename Matrix6Like>
500 void calc_aba(JointDataDerived & data,
const Eigen::MatrixBase<Matrix6Like> & I,
const bool update_I)
const 502 data.U.template leftCols<2>() = I.template leftCols<2>();
503 data.U.template rightCols<1>() = I.template rightCols<1>();
505 data.StU.template leftCols<2>() = data.U.template topRows<2>().transpose();
506 data.StU.template rightCols<1>() = data.U.template bottomRows<1>();
509 data.Dinv.setIdentity();
510 data.StU.llt().solveInPlace(data.Dinv);
512 data.UDinv.noalias() = data.U * data.Dinv;
515 PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like,I) -= data.UDinv * data.U.transpose();
521 return 2.*sqrt(sqrt(Eigen::NumTraits<Scalar>::epsilon()));
524 static std::string classname() {
return std::string(
"JointModelPlanar");}
525 std::string
shortname()
const {
return classname(); }
528 template<
typename NewScalar>
541 #include <boost/type_traits.hpp> 545 template<
typename Scalar,
int Options>
547 :
public integral_constant<bool,true> {};
549 template<
typename Scalar,
int Options>
551 :
public integral_constant<bool,true> {};
553 template<
typename Scalar,
int Options>
555 :
public integral_constant<bool,true> {};
557 template<
typename Scalar,
int Options>
559 :
public integral_constant<bool,true> {};
562 #endif // ifndef __pinocchio_joint_planar_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...
JointModelPlanarTpl< 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...
ConstAngularType angular() const
Return the angular part of the force vector.
Main pinocchio namespace.
Common traits structure to fully define base classes for CRTP.
ConstLinearType linear() const
Return the linear part of the force vector.
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...