19 #ifndef __se3_joint_planar_hpp__ 20 #define __se3_joint_planar_hpp__ 22 #include "pinocchio/macros.hpp" 23 #include "pinocchio/multibody/joint/joint-base.hpp" 24 #include "pinocchio/multibody/constraint.hpp" 25 #include "pinocchio/math/sincos.hpp" 26 #include "pinocchio/spatial/motion.hpp" 27 #include "pinocchio/spatial/inertia.hpp" 34 template<
typename _Scalar,
int _Options>
37 typedef _Scalar Scalar;
38 enum { Options = _Options };
39 typedef Eigen::Matrix<Scalar,3,1,Options> Vector3;
40 typedef Eigen::Matrix<Scalar,6,1,Options> Vector6;
41 typedef Eigen::Matrix<Scalar,6,6,Options> Matrix6;
42 typedef typename EIGEN_REF_CONSTTYPE(Vector6) ToVectorConstReturnType;
43 typedef typename EIGEN_REF_TYPE(Vector6) ToVectorReturnType;
44 typedef Vector3 AngularType;
45 typedef Vector3 LinearType;
46 typedef const Vector3 ConstAngularType;
47 typedef const Vector3 ConstLinearType;
48 typedef Matrix6 ActionMatrixType;
56 template<
typename _Scalar,
int _Options>
64 : m_x_dot(x_dot), m_y_dot(y_dot), m_theta_dot(theta_dot)
69 return MotionPlain(
typename MotionPlain::Vector3(m_x_dot,m_y_dot,Scalar(0)),
70 typename MotionPlain::Vector3(Scalar(0),Scalar(0),m_theta_dot));
73 template<
typename Derived>
76 v.linear()[0] += m_x_dot;
77 v.linear()[1] += m_y_dot;
78 v.angular()[2] += m_theta_dot;
88 template<
typename Scalar,
int Options,
typename MotionDerived>
89 inline typename MotionDerived::MotionPlain
92 typename MotionDerived::MotionPlain result(m2);
93 result.linear()[0] += m1.m_x_dot;
94 result.linear()[1] += m1.m_y_dot;
96 result.angular()[2] += m1.m_theta_dot;
103 template<
typename _Scalar,
int _Options>
106 typedef _Scalar Scalar;
107 enum { Options = _Options };
108 typedef Eigen::Matrix<Scalar,3,1,Options> Vector3;
109 typedef Eigen::Matrix<Scalar,4,1,Options> Vector4;
110 typedef Eigen::Matrix<Scalar,6,1,Options> Vector6;
111 typedef Eigen::Matrix<Scalar,3,3,Options> Matrix3;
112 typedef Eigen::Matrix<Scalar,4,4,Options> Matrix4;
113 typedef Eigen::Matrix<Scalar,6,6,Options> Matrix6;
114 typedef Matrix3 Angular_t;
115 typedef Vector3 Linear_t;
116 typedef const Matrix3 ConstAngular_t;
117 typedef const Vector3 ConstLinear_t;
118 typedef Matrix6 ActionMatrix_t;
119 typedef Eigen::Quaternion<Scalar,Options> Quaternion_t;
128 typedef Eigen::Matrix<Scalar,3,1,Options> JointMotion;
129 typedef Eigen::Matrix<Scalar,3,1,Options> JointForce;
130 typedef Eigen::Matrix<Scalar,6,3,Options> DenseBase;
131 typedef DenseBase MatrixReturnType;
132 typedef const DenseBase ConstMatrixReturnType;
135 template<
typename _Scalar,
int _Options>
140 enum { NV = 3, Options = 0 };
145 template<
typename S1,
int O1>
150 int nv_impl()
const {
return NV; }
157 template<
typename Derived>
165 template<
typename Derived>
166 friend typename Eigen::Matrix <typename Eigen::MatrixBase<Derived>::Scalar, 3, Derived::ColsAtCompileTime>
169 typedef typename Eigen::MatrixBase<Derived>::Scalar Scalar;
170 typedef Eigen::Matrix<Scalar, 3, Derived::ColsAtCompileTime> MatrixReturnType;
173 MatrixReturnType result(3, F.cols ());
174 result.template topRows<2>() = F.template topRows<2>();
175 result.template bottomRows<1>() = F.template bottomRows<1>();
183 DenseBase matrix_impl()
const 186 S.template block<3,3>(Inertia::LINEAR, 0).setZero ();
187 S.template block<3,3>(Inertia::ANGULAR, 0).setZero ();
188 S(Inertia::LINEAR + 0,0) = Scalar(1);
189 S(Inertia::LINEAR + 1,1) = Scalar(1);
190 S(Inertia::ANGULAR + 2,2) = Scalar(1);
194 template<
typename S1,
int O1>
197 DenseBase X_subspace;
198 X_subspace.template block <3,2>(Motion::LINEAR, 0) = m.rotation ().template leftCols <2> ();
199 X_subspace.template block <3,1>(Motion::LINEAR, 2) = m.translation().cross(m.rotation ().template rightCols<1>());
201 X_subspace.template block <3,2>(Motion::ANGULAR, 0).setZero ();
202 X_subspace.template block <3,1>(Motion::ANGULAR, 2) = m.rotation ().template rightCols<1>();
207 template<
typename MotionDerived>
210 const typename MotionDerived::ConstLinearType v = m.linear();
211 const typename MotionDerived::ConstAngularType w = m.angular();
212 DenseBase res(DenseBase::Zero());
214 res(0,1) = -w[2]; res(0,2) = v[1];
215 res(1,0) = w[2]; res(1,2) = -v[0];
216 res(2,0) = -w[1]; res(2,1) = w[0];
224 template<
typename Scalar,
int Options,
typename MatrixDerived>
227 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(MatrixDerived,3);
230 ReturnType result(ReturnType::Zero());
231 result.linear().template head<2> () = v.template topRows<2>();
232 result.angular().template tail<1> () = v.template bottomRows<1>();
236 template<
typename MotionDerived,
typename S2,
int O2>
239 typename MotionDerived::MotionPlain result;
240 typedef typename MotionDerived::Scalar Scalar;
242 const typename MotionDerived::ConstLinearType & m1_t = m1.linear();
243 const typename MotionDerived::ConstAngularType & m1_w = m1.angular();
246 << m1_w(1) * m2.m_theta_dot
247 , - m1_w(0) * m2.m_theta_dot
251 << m1_t(1) * m2.m_theta_dot - m1_w(2) * m2.m_y_dot
252 , - m1_t(0) * m2.m_theta_dot + m1_w(2) * m2.m_x_dot
253 , m1_w(0) * m2.m_y_dot - m1_w(1) * m2.m_x_dot;
259 template<
typename S1,
int O1,
typename S2,
int O2>
260 inline typename Eigen::Matrix<S1,6,3,O1>
264 typedef typename Inertia::Scalar Scalar;
265 typedef Eigen::Matrix<S1,6,3,O1> ReturnType;
268 const Scalar mass = Y.mass();
269 const typename Inertia::Vector3 & com = Y.lever();
270 const typename Inertia::Symmetric3 & inertia = Y.inertia();
272 M.template topLeftCorner<3,3>().setZero();
273 M.template topLeftCorner<2,2>().diagonal().fill(mass);
275 const typename Inertia::Vector3 mc(mass * com);
276 M.template rightCols<1>().
template head<2>() << -mc(1), mc(0);
278 M.template bottomLeftCorner<3,2>() << 0., -mc(2), mc(2), 0., -mc(1), mc(0);
279 M.template rightCols<1>().
template tail<3>() = inertia.data().template tail<3>();
280 M.template rightCols<1>()[3] -= mc(0)*com(2);
281 M.template rightCols<1>()[4] -= mc(1)*com(2);
282 M.template rightCols<1>()[5] += mass*(com(0)*com(0) + com(1)*com(1));
290 template<
typename M6Like,
typename S2,
int O2>
291 inline Eigen::Matrix<S2,6,3,O2>
292 operator*(
const Eigen::MatrixBase<M6Like> & Y,
295 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(M6Like,6,6);
296 typedef Eigen::Matrix<S2,6,3,O2> Matrix63;
299 IS.template leftCols<2>() = Y.template leftCols<2>();
300 IS.template rightCols<1>() = Y.template rightCols<1>();
307 template<
typename S1,
int O1>
308 struct SE3GroupAction< ConstraintPlanarTpl<S1,O1> >
309 {
typedef Eigen::Matrix<S1,6,3,O1> ReturnType; };
311 template<
typename S1,
int O1,
typename MotionDerived>
312 struct MotionAlgebraAction< ConstraintPlanarTpl<S1,O1>,MotionDerived >
313 {
typedef Eigen::Matrix<S1,6,3,O1> ReturnType; };
318 template<
typename _Scalar,
int _Options>
325 enum { Options = _Options };
326 typedef _Scalar Scalar;
333 typedef Eigen::Matrix<Scalar,6,NV,Options> F_t;
336 typedef Eigen::Matrix<Scalar,6,NV,Options> U_t;
337 typedef Eigen::Matrix<Scalar,NV,NV,Options> D_t;
338 typedef Eigen::Matrix<Scalar,6,NV,Options> UD_t;
340 typedef Eigen::Matrix<Scalar,NQ,1,Options> ConfigVector_t;
341 typedef Eigen::Matrix<Scalar,NV,1,Options> TangentVector_t;
344 template<
typename Scalar,
int Options>
346 template<
typename Scalar,
int Options>
349 template<
typename _Scalar,
int _Options>
353 SE3_JOINT_TYPEDEF_TEMPLATE;
371 template<
typename _Scalar,
int _Options>
375 SE3_JOINT_TYPEDEF_TEMPLATE;
382 JointDataDerived
createData()
const {
return JointDataDerived(); }
385 inline void forwardKinematics(Transformation_t & M,
const Eigen::MatrixBase<V> & q_joint)
const 387 EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(ConfigVector_t,V);
389 const double& c_theta = q_joint(2),
390 s_theta = q_joint(3);
392 M.rotation().template topLeftCorner<2,2>() << c_theta, -s_theta, s_theta, c_theta;
393 M.translation().template head<2>() = q_joint.template head<2>();
396 template<
typename ConfigVector>
397 void calc(JointDataDerived & data,
398 const typename Eigen::MatrixBase<ConfigVector> & qs)
const 400 EIGEN_STATIC_ASSERT_VECTOR_ONLY(ConfigVector);
402 typedef typename ConfigVector::Scalar Scalar;
403 typename ConfigVector::template ConstFixedSegmentReturnType<NQ>::Type & q = qs.template segment<NQ>(
idx_q());
409 data.M.rotation().template topLeftCorner<2,2>() << c_theta, -s_theta, s_theta, c_theta;
410 data.M.translation().template head<2>() = q.template head<2>();
414 template<
typename ConfigVector,
typename TangentVector>
415 void calc(JointDataDerived & data,
416 const typename Eigen::MatrixBase<ConfigVector> & qs,
417 const typename Eigen::MatrixBase<TangentVector> & vs)
const 419 EIGEN_STATIC_ASSERT_VECTOR_ONLY(TangentVector);
420 calc(data,qs.derived());
422 typename TangentVector::template ConstFixedSegmentReturnType<NV>::Type & q_dot = vs.template segment<NV>(
idx_v ());
424 data.v.m_x_dot = q_dot(0);
425 data.v.m_y_dot = q_dot(1);
426 data.v.m_theta_dot = q_dot(2);
429 template<
typename S2,
int O2>
430 void calc_aba(JointDataDerived & data, Eigen::Matrix<S2,6,6,O2> & I,
const bool update_I)
const 432 data.U.template leftCols<2>() = I.template leftCols<2>();
433 data.U.template rightCols<1>() = I.template rightCols<1>();
434 Eigen::Matrix<S2,3,3,O2> tmp;
435 tmp.template leftCols<2>() = data.U.template topRows<2>().transpose();
436 tmp.template rightCols<1>() = data.U.template bottomRows<1>();
437 data.Dinv = tmp.inverse();
438 data.UDinv.noalias() = data.U * data.Dinv;
441 I -= data.UDinv * data.U.transpose();
447 return 2.*sqrt(sqrt(Eigen::NumTraits<Scalar>::epsilon()));
450 static std::string classname() {
return std::string(
"JointModelPlanar");}
451 std::string
shortname()
const {
return classname(); }
457 #endif // ifndef __se3_joint_planar_hpp__
JointDataVariant createData(const JointModelVariant &jmodel)
Visit a JointModelVariant through CreateData visitor to create a JointDataVariant.
ConstAngularType angular() const
Return the angular part of the force vector.
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...
ConstLinearType linear() const
Return the linear part of the force vector.
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...