Go to the documentation of this file.
6 #ifndef __pinocchio_multibody_joint_spherical_hpp__
7 #define __pinocchio_multibody_joint_spherical_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 MotionSphericalTpl : MotionBase<MotionSphericalTpl<_Scalar, _Options>>
67 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
75 template<
typename Vector3Like>
90 inline PlainReturnType
plain()
const
92 return PlainReturnType(PlainReturnType::Vector3::Zero(),
m_w);
95 template<
typename MotionDerived>
101 template<
typename Derived>
118 template<
typename MotionDerived>
124 template<
typename S2,
int O2,
typename D2>
128 v.angular().noalias() =
m.rotation() *
m_w;
131 v.linear().noalias() =
m.translation().cross(
v.angular());
134 template<
typename S2,
int O2>
142 template<
typename S2,
int O2,
typename D2>
148 v3_tmp.noalias() =
m_w.cross(
m.translation());
149 v.linear().noalias() =
m.rotation().transpose() * v3_tmp;
152 v.angular().noalias() =
m.rotation().transpose() *
m_w;
155 template<
typename S2,
int O2>
163 template<
typename M1,
typename M2>
167 mout.
linear().noalias() =
v.linear().cross(
m_w);
173 template<
typename M1>
194 template<
typename S1,
int O1,
typename MotionDerived>
195 inline typename MotionDerived::MotionPlain
198 return typename MotionDerived::MotionPlain(m2.
linear(), m2.
angular() + m1.angular());
201 template<
typename Scalar,
int Options>
204 template<
typename _Scalar,
int _Options>
228 template<
typename _Scalar,
int _Options>
232 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
250 template<
typename Vector3Like>
251 JointMotion
__mult__(
const Eigen::MatrixBase<Vector3Like> &
w)
const
253 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3);
254 return JointMotion(
w);
259 template<
typename Derived>
266 template<
typename MatrixDerived>
268 operator*(
const Eigen::MatrixBase<MatrixDerived> & F)
const
270 assert(F.rows() == 6);
271 return F.derived().template middleRows<3>(Inertia::ANGULAR);
283 S.template block<3, 3>(LINEAR, 0).setZero();
284 S.template block<3, 3>(ANGULAR, 0).setIdentity();
288 template<
typename S1,
int O1>
291 Eigen::Matrix<S1, 6, 3, O1> X_subspace;
292 cross(
m.translation(),
m.rotation(), X_subspace.template middleRows<3>(LINEAR));
293 X_subspace.template middleRows<3>(ANGULAR) =
m.rotation();
298 template<
typename S1,
int O1>
301 Eigen::Matrix<S1, 6, 3, O1> X_subspace;
302 XAxis::cross(
m.translation(), X_subspace.template middleRows<3>(ANGULAR).col(0));
303 YAxis::cross(
m.translation(), X_subspace.template middleRows<3>(ANGULAR).col(1));
304 ZAxis::cross(
m.translation(), X_subspace.template middleRows<3>(ANGULAR).col(2));
306 X_subspace.template middleRows<3>(LINEAR).noalias() =
307 m.rotation().transpose() * X_subspace.template middleRows<3>(ANGULAR);
308 X_subspace.template middleRows<3>(ANGULAR) =
m.rotation().transpose();
313 template<
typename MotionDerived>
316 const typename MotionDerived::ConstLinearType
v =
m.linear();
317 const typename MotionDerived::ConstAngularType
w =
m.angular();
320 skew(
v,
res.template middleRows<3>(LINEAR));
321 skew(
w,
res.template middleRows<3>(ANGULAR));
333 template<
typename MotionDerived,
typename S2,
int O2>
334 inline typename MotionDerived::MotionPlain
337 return m2.motionAction(m1);
341 template<
typename S1,
int O1,
typename S2,
int O2>
342 inline Eigen::Matrix<S2, 6, 3, O2>
347 Eigen::Matrix<S2, 6, 3, O2>
M;
349 M.template block<3, 3>(Inertia::LINEAR, 0) =
alphaSkew(-
Y.mass(),
Y.lever());
350 M.template block<3, 3>(Inertia::ANGULAR, 0) =
351 (
Y.inertia() -
typename Symmetric3::AlphaSkewSquare(
Y.mass(),
Y.lever())).matrix();
356 template<
typename M6Like,
typename S2,
int O2>
357 inline typename SizeDepType<3>::ColsReturn<M6Like>::ConstType
361 return Y.derived().template middleCols<3>(Constraint::ANGULAR);
364 template<
typename S1,
int O1>
370 template<
typename S1,
int O1,
typename MotionDerived>
376 template<
typename Scalar,
int Options>
379 template<
typename _Scalar,
int _Options>
400 typedef Eigen::Matrix<Scalar, 6, NV, Options>
U_t;
401 typedef Eigen::Matrix<Scalar, NV, NV, Options>
D_t;
402 typedef Eigen::Matrix<Scalar, 6, NV, Options>
UD_t;
410 template<
typename _Scalar,
int _Options>
417 template<
typename _Scalar,
int _Options>
424 template<
typename _Scalar,
int _Options>
427 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
449 ,
joint_v(TangentVector_t::Zero())
450 ,
M(Transformation_t::Identity())
454 ,
UDinv(UD_t::Zero())
461 return std::string(
"JointDataSpherical");
471 template<
typename _Scalar,
int _Options>
472 struct JointModelSphericalTpl :
public JointModelBase<JointModelSphericalTpl<_Scalar, _Options>>
474 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
487 return JointDataDerived();
492 return {
false,
false,
false,
false};
497 return {
false,
false,
false};
500 template<
typename ConfigVectorLike>
502 Transformation_t & M,
const Eigen::MatrixBase<ConfigVectorLike> & q_joint)
const
505 EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(ConfigVector_t, ConfigVectorLike);
509 typedef Eigen::Map<const Quaternion> ConstQuaternionMap;
511 ConstQuaternionMap
quat(q_joint.derived().data());
514 assert(math::fabs(
static_cast<Scalar>(
quat.coeffs().squaredNorm() - 1)) <= 1e-4);
516 M.rotation(
quat.matrix());
517 M.translation().setZero();
520 template<
typename QuaternionDerived>
522 JointDataDerived &
data,
const typename Eigen::QuaternionBase<QuaternionDerived> & quat)
const
528 template<
typename ConfigVector>
529 EIGEN_DONT_INLINE
void
530 calc(JointDataDerived &
data,
const typename Eigen::PlainObjectBase<ConfigVector> &
qs)
const
532 typedef typename Eigen::Quaternion<typename ConfigVector::Scalar, ConfigVector::Options>
534 typedef Eigen::Map<const Quaternion> ConstQuaternionMap;
540 template<
typename ConfigVector>
541 EIGEN_DONT_INLINE
void
542 calc(JointDataDerived &
data,
const typename Eigen::MatrixBase<ConfigVector> &
qs)
const
544 typedef typename Eigen::Quaternion<Scalar, Options>
Quaternion;
550 template<
typename TangentVector>
552 calc(JointDataDerived &
data,
const Blank,
const typename Eigen::MatrixBase<TangentVector> & vs)
555 data.joint_v = vs.template segment<NV>(
idx_v());
559 template<
typename ConfigVector,
typename TangentVector>
561 JointDataDerived &
data,
562 const typename Eigen::MatrixBase<ConfigVector> &
qs,
563 const typename Eigen::MatrixBase<TangentVector> & vs)
const
566 data.joint_v = vs.template segment<NV>(
idx_v());
570 template<
typename VectorLike,
typename Matrix6Like>
572 JointDataDerived &
data,
573 const Eigen::MatrixBase<VectorLike> & armature,
574 const Eigen::MatrixBase<Matrix6Like> & I,
575 const bool update_I)
const
577 data.U = I.template block<6, 3>(0, Inertia::ANGULAR);
578 data.StU =
data.U.template middleRows<3>(Inertia::ANGULAR);
579 data.StU.diagonal() += armature;
590 return std::string(
"JointModelSpherical");
598 template<
typename NewScalar>
611 #include <boost/type_traits.hpp>
615 template<
typename Scalar,
int Options>
617 :
public integral_constant<bool, true>
621 template<
typename Scalar,
int Options>
623 :
public integral_constant<bool, true>
627 template<
typename Scalar,
int Options>
629 :
public integral_constant<bool, true>
633 template<
typename Scalar,
int Options>
635 :
public integral_constant<bool, true>
640 #endif // ifndef __pinocchio_multibody_joint_spherical_hpp__
DenseBase matrix_impl() const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW MOTION_TYPEDEF_TPL(MotionSphericalTpl)
JointSphericalTpl< _Scalar, _Options > JointDerived
Eigen::Matrix< Scalar, 3, 1, Options > JointForce
MotionSphericalTpl< context::Scalar > MotionSpherical
#define PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
Symmetric3Tpl< context::Scalar, context::Options > Symmetric3
Eigen::Matrix< Scalar, NQ, 1, Options > ConfigVector_t
MotionSphericalTpl< Scalar, Options > Motion_t
Eigen::Matrix< Scalar, 6, 3, Options > DenseBase
const SizeDepType< 3 >::RowsReturn< MatrixDerived >::ConstType operator*(const Eigen::MatrixBase< MatrixDerived > &F) const
static void cross(const Eigen::MatrixBase< V3_in > &vin, const Eigen::MatrixBase< V3_out > &vout)
void addTo(MotionDense< MotionDerived > &other) const
static std::string classname()
JointSphericalTpl< _Scalar, _Options > JointDerived
int idx_q(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxQVisitor to get the index in the full model configuration space...
ForceDense< Derived >::ConstAngularType operator*(const ForceDense< Derived > &phi)
MotionTpl< Scalar, Options > ReturnType
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs, const typename Eigen::MatrixBase< TangentVector > &vs) 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...
MotionSphericalTpl(const Eigen::MatrixBase< Vector3Like > &w)
InertiaTpl< context::Scalar, context::Options > Inertia
JointDataSphericalTpl< Scalar, Options > JointDataDerived
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
bool isEqual_impl(const MotionSphericalTpl &other) const
MotionPlain se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m) const
static std::string classname()
EIGEN_DONT_INLINE void calc(JointDataDerived &data, const typename Eigen::PlainObjectBase< ConfigVector > &qs) const
PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like) operator*(const Eigen
DenseBase MatrixReturnType
MotionDerived::MotionPlain operator+(const MotionHelicalUnalignedTpl< S1, O1 > &m1, const MotionDense< MotionDerived > &m2)
std::string shortname() const
Matrix4 HomogeneousMatrixType
MotionTpl< Scalar, Options > MotionPlain
void setIndexes(JointIndex id, int q, int v)
const typedef DenseBase ConstMatrixReturnType
MotionSphericalTpl __plus__(const MotionSphericalTpl &other) const
Return type of the ation of a Motion onto an object of type D.
void calc_aba(JointDataDerived &data, const Eigen::MatrixBase< VectorLike > &armature, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const
TridiagonalSymmetricMatrixApplyOnTheLeftReturnType< LhsMatrixType, TridiagonalSymmetricMatrixTpl< S, O > > operator*(const Eigen::MatrixBase< LhsMatrixType > &lhs, const TridiagonalSymmetricMatrixTpl< S, O > &rhs)
const std::vector< bool > hasConfigurationLimitInTangent() const
ConstLinearType linear() const
const typedef Vector3 ConstAngularType
MotionPlain motionAction(const MotionDense< M1 > &v) const
void calc(JointDataDerived &data, const Blank, const typename Eigen::MatrixBase< TangentVector > &vs) const
#define PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR
JointMotionSubspaceSphericalTpl< Scalar, Options > Constraint_t
Eigen::Quaternion< Scalar, Options > Quaternion
Eigen::Matrix< S1, 6, 3, O1 > se3Action(const SE3Tpl< S1, O1 > &m) const
Symmetric3Tpl< Scalar, Options > Symmetric3
PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(JointDerived)
void motionAction(const MotionDense< M1 > &v, MotionDense< M2 > &mout) const
const Vector3 & operator()() const
Eigen::Matrix< Scalar, 6, 1, Options > Vector6
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION(JointModelFreeFlyerTpl)
Free-flyer joint in .
void skew(const Eigen::MatrixBase< Vector3 > &v, const Eigen::MatrixBase< Matrix3 > &M)
Computes the skew representation of a given 3d vector, i.e. the antisymmetric matrix representation o...
Eigen::Matrix< Scalar, NV, 1, Options > TangentVector_t
MotionSphericalTpl< Scalar, Options > JointMotion
JointModelBase< JointModelSphericalTpl > Base
std::string shortname() const
JointMotion __mult__(const Eigen::MatrixBase< Vector3Like > &w) const
Eigen::Matrix< Scalar, NV, NV, Options > D_t
void setTo(MotionDense< Derived > &other) const
const std::vector< bool > hasConfigurationLimit() const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointSphericalTpl< _Scalar, _Options > JointDerived
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
MotionTpl< Scalar, Options > ReturnType
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointSphericalTpl< _Scalar, _Options > JointDerived
bool isEqual_impl(const MotionDense< MotionDerived > &other) const
TransposeConst transpose() const
DenseBase motionAction(const MotionDense< MotionDerived > &m) const
Eigen::Matrix< Scalar, 4, 4, Options > Matrix4
void forwardKinematics(Transformation_t &M, const Eigen::MatrixBase< ConfigVectorLike > &q_joint) const
void se3Action_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
bool comparison_eq(const LhsType &lhs_value, const RhsType &rhs_value)
Eigen::Matrix< S1, 6, 3, O1 > se3ActionInverse(const SE3Tpl< S1, O1 > &m) const
const typedef Vector3 ConstLinearType
PlainReturnType plain() const
MotionPlain PlainReturnType
void se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) 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.
Eigen::Matrix< Scalar, 3, 3, Options > ReducedSquaredMatrix
EIGEN_STRONG_INLINE MotionDerived::MotionPlain operator^(const MotionDense< MotionDerived > &m1, const MotionHelicalUnalignedTpl< S2, O2 > &m2)
MotionZeroTpl< Scalar, Options > Bias_t
Eigen::Matrix< S1, 6, 3, O1 > ReturnType
#define PINOCCHIO_CONSTRAINT_TYPEDEF_TPL(DERIVED)
bool isEqual(const JointMotionSubspaceSphericalTpl &) const
JointModelSphericalTpl< Scalar, Options > JointModelDerived
Common traits structure to fully define base classes for CRTP.
Eigen::Matrix< Scalar, 6, NV, Options > UD_t
void calc(JointDataDerived &data, const typename Eigen::QuaternionBase< QuaternionDerived > &quat) const
PINOCCHIO_EIGEN_PLAIN_TYPE(ConfigVectorType) integrate(const ModelTpl< Scalar
Integrate a configuration vector for the specified model for a tangent vector during one unit time.
PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR ConfigVector_t joint_q
MotionPlain se3Action_impl(const SE3Tpl< S2, O2 > &m) const
#define PINOCCHIO_EIGEN_REF_TYPE(D)
EIGEN_DONT_INLINE void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs) const
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....
const Vector3 & angular() const
Eigen::Matrix< Scalar, 6, 6, Options > Matrix6
Eigen::Matrix< Scalar, 6, NV, Options > U_t
ReducedSquaredMatrix::IdentityReturnType StDiagonalMatrixSOperationReturnType
ConstAngularType angular() const
Return the angular part of the force vector.
ConstAngularType angular() const
JointDataDerived createData() const
Eigen::Matrix< S1, 6, 3, O1 > ReturnType
Main pinocchio namespace.
PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(JointDerived)
SE3Tpl< Scalar, Options > Transformation_t
JointModelSphericalTpl< NewScalar, Options > cast() const
pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:46