6 #ifndef __pinocchio_joint_spherical_ZYX_hpp__ 7 #define __pinocchio_joint_spherical_ZYX_hpp__ 9 #include "pinocchio/macros.hpp" 10 #include "pinocchio/multibody/joint/joint-base.hpp" 11 #include "pinocchio/multibody/joint/joint-spherical.hpp" 12 #include "pinocchio/multibody/constraint.hpp" 13 #include "pinocchio/math/sincos.hpp" 14 #include "pinocchio/math/matrix.hpp" 15 #include "pinocchio/spatial/inertia.hpp" 16 #include "pinocchio/spatial/skew.hpp" 22 template <
typename _Scalar,
int _Options>
35 typedef Eigen::Matrix<Scalar,6,3,Options>
DenseBase;
41 template<
typename _Scalar,
int _Options>
43 :
public ConstraintBase< ConstraintSphericalZYXTpl<_Scalar,_Options> >
45 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
50 typedef Eigen::Matrix<Scalar,3,3,Options>
Matrix3;
54 template<
typename Matrix3Like>
57 { EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix3Like,3,3); }
59 template<
typename Vector3Like>
60 JointMotion
__mult__(
const Eigen::MatrixBase<Vector3Like> &
v)
const 62 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like,3);
63 return JointMotion(m_S * v);
66 Matrix3 & operator() () {
return m_S; }
67 const Matrix3 & operator() ()
const {
return m_S; }
76 template<
typename Derived>
78 Eigen::Transpose<const Matrix3>,
79 Eigen::Block<const typename ForceDense<Derived>::Vector6,3,1>
89 typename Eigen::Transpose<const Matrix3>,
90 typename Eigen::MatrixBase<const D>::template NRowsBlockXpr<3>::Type
94 EIGEN_STATIC_ASSERT(D::RowsAtCompileTime==6,THIS_METHOD_IS_ONLY_FOR_MATRICES_OF_A_SPECIFIC_SIZE)
95 return ref.
m_S.transpose () * F.template middleRows<3>(ANGULAR);
104 S.template middleRows<3>(LINEAR).setZero();
105 S.template middleRows<3>(ANGULAR) = m_S;
113 template<
typename S1,
int O1>
114 Eigen::Matrix<Scalar,6,3,Options>
123 Eigen::Matrix<Scalar,6,3,Options> result;
126 result.template middleRows<3>(ANGULAR).noalias() = m.
rotation () * m_S;
130 result.template middleRows<3>(Motion::ANGULAR),
131 result.template middleRows<3>(LINEAR));
136 template<
typename S1,
int O1>
137 Eigen::Matrix<Scalar,6,3,Options>
140 Eigen::Matrix<Scalar,6,3,Options> result;
145 result.template middleRows<3>(ANGULAR));
146 result.template middleRows<3>(LINEAR).noalias() = -m.
rotation().transpose() * result.template middleRows<3>(ANGULAR);
149 result.template middleRows<3>(ANGULAR).noalias() = m.
rotation().transpose() * m_S;
154 template<
typename MotionDerived>
157 const typename MotionDerived::ConstLinearType
v = m.
linear();
158 const typename MotionDerived::ConstAngularType
w = m.
angular();
161 cross(v,m_S,res.template middleRows<3>(LINEAR));
162 cross(w,m_S,res.template middleRows<3>(ANGULAR));
172 return m_S == other.
m_S;
181 template <
typename S1,
int O1,
typename S2,
int O2>
182 Eigen::Matrix<S1,6,3,O1>
188 Eigen::Matrix<S1,6,3,O1>
M;
190 M.template middleRows<3>(Constraint::ANGULAR) = (Y.
inertia () -
191 typename Symmetric3::AlphaSkewSquare(Y.
mass (), Y.
lever ())).matrix();
198 template<
typename Matrix6Like,
typename S2,
int O2>
200 typename Eigen::internal::remove_const<typename SizeDepType<3>::ColsReturn<Matrix6Like>::ConstType>
::type,
206 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix6Like,6,6);
207 return Y.derived().template middleCols<3>(Inertia::ANGULAR) * S.
angularSubspace();
210 template<
typename S1,
int O1>
220 template<
typename S1,
int O1,
typename MotionDerived>
228 template<
typename _Scalar,
int _Options>
245 typedef Eigen::Matrix<Scalar,6,NV,Options>
U_t;
246 typedef Eigen::Matrix<Scalar,NV,NV,Options>
D_t;
247 typedef Eigen::Matrix<Scalar,6,NV,Options>
UD_t;
255 template<
typename Scalar,
int Options>
259 template<
typename Scalar,
int Options>
263 template<
typename _Scalar,
int _Options>
266 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
283 : S(Constraint_t::Matrix3::Zero())
284 , M(Transformation_t::Identity())
285 , v(Motion_t::Vector3::Zero())
286 , c(Bias_t::Vector3::Zero())
289 , UDinv(UD_t::Zero())
292 static std::string
classname() {
return std::string(
"JointDataSphericalZYX"); }
298 template<
typename _Scalar,
int _Options>
300 :
public JointModelBase< JointModelSphericalZYXTpl<_Scalar,_Options> >
302 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
312 JointDataDerived
createData()
const {
return JointDataDerived(); }
314 template<
typename ConfigVector>
315 void calc(JointDataDerived & data,
316 const typename Eigen::MatrixBase<ConfigVector> & qs)
const 318 typename ConfigVector::template ConstFixedSegmentReturnType<NQ>::Type &
q = qs.template segment<NQ>(
idx_q());
322 S2 c0,s0;
SINCOS(
q(0), &s0, &c0);
323 S2 c1,s1;
SINCOS(
q(1), &s1, &c1);
324 S2 c2,s2;
SINCOS(
q(2), &s2, &c2);
326 data.M.rotation () << c0 * c1,
327 c0 * s1 * s2 - s0 * c2,
328 c0 * s1 * c2 + s0 * s2,
330 s0 * s1 * s2 + c0 * c2,
331 s0 * s1 * c2 - c0 * s2,
336 data.S.angularSubspace()
342 template<
typename ConfigVector,
typename TangentVector>
343 void calc(JointDataDerived & data,
344 const typename Eigen::MatrixBase<ConfigVector> & qs,
345 const typename Eigen::MatrixBase<TangentVector> & vs)
const 347 typename ConfigVector::template ConstFixedSegmentReturnType<NQ>::Type &
q = qs.template segment<NQ>(
idx_q());
351 S2 c0,s0;
SINCOS(
q(0), &s0, &c0);
352 S2 c1,s1;
SINCOS(
q(1), &s1, &c1);
353 S2 c2,s2;
SINCOS(
q(2), &s2, &c2);
355 data.M.rotation () << c0 * c1,
356 c0 * s1 * s2 - s0 * c2,
357 c0 * s1 * c2 + s0 * s2,
359 s0 * s1 * s2 + c0 * c2,
360 s0 * s1 * c2 - c0 * s2,
365 data.S.angularSubspace()
370 typename TangentVector::template ConstFixedSegmentReturnType<NV>::Type
371 & q_dot = vs.template segment<NV>(
idx_v());
373 data.v().noalias() = data.S.angularSubspace() * q_dot;
375 data.c()(0) = -c1 * q_dot(0) * q_dot(1);
376 data.c()(1) = -s1 * s2 * q_dot(0) * q_dot(1) + c1 * c2 * q_dot(0) * q_dot(2) - s2 * q_dot(1) * q_dot(2);
377 data.c()(2) = -s1 * c2 * q_dot(0) * q_dot(1) - c1 * s2 * q_dot(0) * q_dot(2) - c2 * q_dot(1) * q_dot(2);
380 template<
typename Matrix6Like>
382 const Eigen::MatrixBase<Matrix6Like> & I,
383 const bool update_I)
const 385 data.U.noalias() = I.template middleCols<3>(Motion::ANGULAR) * data.S.angularSubspace();
386 data.StU.noalias() = data.S.angularSubspace().transpose() * data.U.template middleRows<3>(Motion::ANGULAR);
393 data.UDinv.noalias() = data.U * data.Dinv;
399 static std::string
classname() {
return std::string(
"JointModelSphericalZYX"); }
403 template<
typename NewScalar>
416 #include <boost/type_traits.hpp> 420 template<
typename Scalar,
int Options>
422 :
public integral_constant<bool,true> {};
424 template<
typename Scalar,
int Options>
426 :
public integral_constant<bool,true> {};
428 template<
typename Scalar,
int Options>
430 :
public integral_constant<bool,true> {};
432 template<
typename Scalar,
int Options>
434 :
public integral_constant<bool,true> {};
437 #endif // ifndef __pinocchio_joint_spherical_ZYX_hpp__ JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
Eigen::Matrix< Scalar, NV, NV, Options > D_t
Eigen::Matrix< S1, 6, 3, O1 > ReturnType
int idx_q(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxQVisitor to get the index in the full model configuration space...
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...
DenseBase motionAction(const MotionDense< MotionDerived > &m) const
JointDataDerived createData() const
Return type of the ation of a Motion onto an object of type D.
JointDataSphericalZYXTpl< Scalar, Options > JointDataDerived
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointSphericalZYXTpl< _Scalar, _Options > JointDerived
PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR Constraint_t S
JointIndex id(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdVisitor to get the index of the joint in the kinematic chain...
#define PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR
void calc_aba(JointDataDerived &data, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const
Eigen::Matrix< S1, 6, 3, O1 > ReturnType
std::string shortname() const
ConstAngularType angular() const
Return the angular part of the force vector.
bool isEqual(const ConstraintSphericalZYXTpl &other) const
PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE typedef Eigen::Matrix< Scalar, NQ, 1, Options > ConfigVector_t
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
const DenseBase ConstMatrixReturnType
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
Eigen::Matrix< Scalar, 3, 1, Options > JointForce
Eigen::Matrix< Scalar, 6, NV, Options > UD_t
ConstraintSphericalZYXTpl(const Eigen::MatrixBase< Matrix3Like > &subspace)
Eigen::Matrix< Scalar, 6, NV, Options > U_t
Matrix3 & angularSubspace()
static std::string classname()
Eigen::Matrix< Scalar, NV, 1, Options > TangentVector_t
std::string shortname() const
#define PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
ConstraintTranspose transpose() const
const Symmetric3 & inertia() const
const Vector3 & lever() const
MotionSphericalTpl< Scalar, Options > JointMotion
ConstLinearType linear() const
void cross(const Eigen::MatrixBase< Vector3 > &v, const Eigen::MatrixBase< Matrix3xIn > &Min, const Eigen::MatrixBase< Matrix3xOut > &Mout)
Applies the cross product onto the columns of M.
#define PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(Joint)
JointModelSphericalZYXTpl< NewScalar, Options > cast() const
ConstraintSphericalZYXTpl()
MotionSphericalTpl< Scalar, Options > Bias_t
JointSphericalZYXTpl< Scalar, Options > JointDerived
JointDataSphericalZYXTpl()
JointModelSphericalZYXTpl< Scalar, Options > JointModelDerived
ConstLinearRef translation() const
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION(JointModelFreeFlyerTpl)
JointSphericalZYXTpl< Scalar, Options > JointDerived
void SINCOS(const S1 &a, S2 *sa, S3 *ca)
Computes sin/cos values of a given input scalar.
Main pinocchio namespace.
Eigen::Matrix< Scalar, 6, 3, Options > se3Action(const SE3Tpl< S1, O1 > &m) const
Eigen::Matrix< Scalar, 3, 3, Options > Matrix3
JointModelBase< JointModelSphericalZYXTpl > Base
void setIndexes(JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel, JointIndex id, int q, int v)
Visit a JointModelTpl through JointSetIndexesVisitor to set the indexes of the joint in the kinematic...
MotionSphericalTpl< Scalar, Options > Motion_t
void alphaSkew(const Scalar alpha, const Eigen::MatrixBase< Vector3 > &v, const Eigen::MatrixBase< Matrix3 > &M)
Computes the skew representation of a given 3d vector multiplied by a given scalar. i.e. the antisymmetric matrix representation of the cross product operator ( )
DenseBase MatrixReturnType
ConstraintTranspose(const ConstraintSphericalZYXTpl &ref)
Common traits structure to fully define base classes for CRTP.
Symmetric3Tpl< double, 0 > Symmetric3
Eigen::Matrix< Scalar, 6, 3, Options > DenseBase
#define PINOCCHIO_CONSTRAINT_TYPEDEF_TPL(DERIVED)
Eigen::Matrix< Scalar, 6, 3, Options > se3ActionInverse(const SE3Tpl< S1, O1 > &m) const
const Matrix3 & angularSubspace() const
const ConstraintSphericalZYXTpl & ref
ConstAngularType angular() const
JointMotion __mult__(const Eigen::MatrixBase< Vector3Like > &v) const
SE3Tpl< Scalar, Options > Transformation_t
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs, const typename Eigen::MatrixBase< TangentVector > &vs) const
static std::string classname()
ConstAngularRef rotation() const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointSphericalZYXTpl< _Scalar, _Options > JointDerived
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs) const
MultiplicationOp< InertiaTpl< Scalar, Options >, ConstraintDerived >::ReturnType operator*(const InertiaTpl< Scalar, Options > &Y, const ConstraintBase< ConstraintDerived > &constraint)
.
DenseBase matrix_impl() const
ConstraintSphericalZYXTpl< Scalar, Options > Constraint_t
#define PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(Joint)