Go to the documentation of this file.
6 #ifndef __pinocchio_multibody_joint_revolute_hpp__
7 #define __pinocchio_multibody_joint_revolute_hpp__
19 template<
typename Scalar,
int Options,
int axis>
22 template<
typename Scalar,
int Options,
int axis>
28 template<
typename Scalar,
int Options,
int axis,
typename MotionDerived>
34 template<
typename _Scalar,
int _Options,
int axis>
42 typedef Eigen::Matrix<Scalar, 3, 1, Options>
Vector3;
43 typedef Eigen::Matrix<Scalar, 6, 1, Options>
Vector6;
44 typedef Eigen::Matrix<Scalar, 4, 4, Options>
Matrix4;
45 typedef Eigen::Matrix<Scalar, 6, 6, Options>
Matrix6;
63 template<
typename Scalar,
int Options,
int axis>
66 template<
typename _Scalar,
int _Options,
int _axis>
78 typedef Eigen::Matrix<Scalar, 3, 1, Options>
Vector3;
79 typedef Eigen::Matrix<Scalar, 3, 3, Options>
Matrix3;
84 typedef typename Vector3::ConstantReturnType
LinearRef;
90 template<
typename Scalar,
int Options,
int axis>
96 template<
typename _Scalar,
int _Options,
int axis>
99 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
113 PlainType
res(PlainType::Identity());
118 operator PlainType()
const
123 template<
typename S2,
int O2>
132 res.rotation().col(0) =
m.rotation().col(0);
133 res.rotation().col(1).noalias() =
m_cos *
m.rotation().col(1) +
m_sin *
m.rotation().col(2);
134 res.rotation().col(2).noalias() =
res.rotation().col(0).cross(
res.rotation().col(1));
138 res.rotation().col(2).noalias() =
m_cos *
m.rotation().col(2) +
m_sin *
m.rotation().col(0);
139 res.rotation().col(1) =
m.rotation().col(1);
140 res.rotation().col(0).noalias() =
res.rotation().col(1).cross(
res.rotation().col(2));
144 res.rotation().col(0).noalias() =
m_cos *
m.rotation().col(0) +
m_sin *
m.rotation().col(1);
145 res.rotation().col(1).noalias() =
res.rotation().col(2).cross(
res.rotation().col(0));
146 res.rotation().col(2) =
m.rotation().col(2);
150 assert(
false &&
"must never happened");
154 res.translation() =
m.translation();
176 template<
typename OtherScalar>
185 return LinearType::PlainObject::Zero(3);
189 AngularType
m(AngularType::Identity());
207 rot.coeffRef(1, 1) =
m_cos;
208 rot.coeffRef(1, 2) = -
m_sin;
209 rot.coeffRef(2, 1) =
m_sin;
210 rot.coeffRef(2, 2) =
m_cos;
214 rot.coeffRef(0, 0) =
m_cos;
215 rot.coeffRef(0, 2) =
m_sin;
216 rot.coeffRef(2, 0) = -
m_sin;
217 rot.coeffRef(2, 2) =
m_cos;
221 rot.coeffRef(0, 0) =
m_cos;
222 rot.coeffRef(0, 1) = -
m_sin;
223 rot.coeffRef(1, 0) =
m_sin;
224 rot.coeffRef(1, 1) =
m_cos;
228 assert(
false &&
"must never happened");
235 template<
typename _Scalar,
int _Options,
int axis>
236 struct MotionRevoluteTpl : MotionBase<MotionRevoluteTpl<_Scalar, _Options, axis>>
238 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
253 template<
typename Vector1Like>
257 using namespace Eigen;
258 EIGEN_STATIC_ASSERT_SIZE_1x1(Vector1Like);
261 inline PlainReturnType
plain()
const
266 template<
typename OtherScalar>
272 template<
typename MotionDerived>
275 m.linear().setZero();
276 for (Eigen::DenseIndex k = 0; k < 3; ++k)
282 template<
typename MotionDerived>
286 v.angular()[
axis] += (OtherScalar)
m_w;
289 template<
typename S2,
int O2,
typename D2>
292 v.angular().noalias() =
m.rotation().col(
axis) *
m_w;
293 v.linear().noalias() =
m.translation().cross(
v.angular());
296 template<
typename S2,
int O2>
304 template<
typename S2,
int O2,
typename D2>
309 v.linear().noalias() =
m.rotation().transpose() *
v.angular();
312 v.angular().noalias() =
m.rotation().transpose().col(
axis) *
m_w;
315 template<
typename S2,
int O2>
323 template<
typename M1,
typename M2>
333 template<
typename M1>
359 template<
typename S1,
int O1,
int axis,
typename MotionDerived>
360 typename MotionDerived::MotionPlain
363 typename MotionDerived::MotionPlain
res(m2);
368 template<
typename MotionDerived,
typename S2,
int O2,
int axis>
369 EIGEN_STRONG_INLINE
typename MotionDerived::MotionPlain
372 return m2.motionAction(m1);
375 template<
typename Scalar,
int Options,
int axis>
378 template<
typename Scalar,
int Options,
int axis>
384 template<
typename Scalar,
int Options,
int axis,
typename MotionDerived>
390 template<
typename Scalar,
int Options,
int axis,
typename ForceDerived>
394 ForceDerived>::ConstAngularType::template ConstFixedSegmentReturnType<1>::Type
ReturnType;
397 template<
typename Scalar,
int Options,
int axis,
typename ForceSet>
400 typedef typename Eigen::MatrixBase<ForceSet>::ConstRowXpr
ReturnType;
403 template<
typename _Scalar,
int _Options,
int axis>
428 template<
typename _Scalar,
int _Options,
int axis>
432 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
446 template<
typename Vector1Like>
447 JointMotion
__mult__(
const Eigen::MatrixBase<Vector1Like> &
v)
const
449 return JointMotion(
v[0]);
452 template<
typename S1,
int O1>
458 res.template segment<3>(LINEAR) =
m.translation().cross(
m.rotation().col(
axis));
459 res.template segment<3>(ANGULAR) =
m.rotation().col(
axis);
463 template<
typename S1,
int O1>
470 res.template segment<3>(LINEAR).noalias() =
472 res.template segment<3>(ANGULAR) =
m.rotation().transpose().col(
axis);
489 template<
typename ForceDerived>
493 return f.angular().template segment<1>(
axis);
497 template<
typename Derived>
501 assert(F.rows() == 6);
502 return F.row(ANGULAR +
axis);
525 template<
typename MotionDerived>
545 template<
typename _Scalar,
int _Options,
int _axis>
557 template<
typename S1,
int O1,
typename S2,
int O2,
int axis>
566 template<
typename S1,
int O1,
typename S2,
int O2>
577 const S1 &
m =
Y.mass(), &
x =
Y.lever()[0], &
y =
Y.lever()[1], &z =
Y.lever()[2];
580 res << (S2)0, -
m * z,
m *
y, I(0, 0) +
m * (
y *
y + z * z), I(0, 1) -
m *
x *
y,
587 template<
typename S1,
int O1,
typename S2,
int O2>
598 const S1 &
m =
Y.mass(), &
x =
Y.lever()[0], &
y =
Y.lever()[1], &z =
Y.lever()[2];
601 res <<
m * z, (S2)0, -
m *
x, I(1, 0) -
m *
x *
y, I(1, 1) +
m * (
x *
x + z * z),
608 template<
typename S1,
int O1,
typename S2,
int O2>
619 const S1 &
m =
Y.mass(), &
x =
Y.lever()[0], &
y =
Y.lever()[1], &z =
Y.lever()[2];
622 res << -
m *
y,
m *
x, (S2)0, I(2, 0) -
m *
x * z, I(2, 1) -
m *
y * z,
623 I(2, 2) +
m * (
x *
x +
y *
y);
630 template<
typename M6Like,
typename S2,
int O2,
int axis>
639 template<
typename M6Like,
typename Scalar,
int Options,
int axis>
641 Eigen::MatrixBase<M6Like>,
650 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(M6Like, 6, 6);
651 return Y.col(Inertia::ANGULAR +
axis);
656 template<
typename _Scalar,
int _Options,
int axis>
677 typedef Eigen::Matrix<Scalar, 6, NV, Options>
U_t;
678 typedef Eigen::Matrix<Scalar, NV, NV, Options>
D_t;
679 typedef Eigen::Matrix<Scalar, 6, NV, Options>
UD_t;
687 template<
typename _Scalar,
int _Options,
int axis>
694 template<
typename _Scalar,
int _Options,
int axis>
701 template<
typename _Scalar,
int _Options,
int axis>
704 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
724 :
joint_q(ConfigVector_t::Zero())
725 ,
joint_v(TangentVector_t::Zero())
730 , UDinv(UD_t::Zero())
737 return std::string(
"JointDataR") + axisLabel<axis>();
746 template<
typename NewScalar,
typename Scalar,
int Options,
int axis>
752 template<
typename _Scalar,
int _Options,
int axis>
754 :
public JointModelBase<JointModelRevoluteTpl<_Scalar, _Options, axis>>
756 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
766 typedef Eigen::Matrix<Scalar, 3, 1, _Options>
Vector3;
770 return JointDataDerived();
787 template<
typename ConfigVector>
788 EIGEN_DONT_INLINE
void
789 calc(JointDataDerived &
data,
const typename Eigen::MatrixBase<ConfigVector> &
qs)
const
794 data.M.setValues(sa, ca);
797 template<
typename TangentVector>
798 EIGEN_DONT_INLINE
void
799 calc(JointDataDerived &
data,
const Blank,
const typename Eigen::MatrixBase<TangentVector> & vs)
803 data.v.angularRate() =
data.joint_v[0];
806 template<
typename ConfigVector,
typename TangentVector>
808 JointDataDerived &
data,
809 const typename Eigen::MatrixBase<ConfigVector> &
qs,
810 const typename Eigen::MatrixBase<TangentVector> & vs)
const
815 data.v.angularRate() =
data.joint_v[0];
818 template<
typename VectorLike,
typename Matrix6Like>
820 JointDataDerived &
data,
821 const Eigen::MatrixBase<VectorLike> & armature,
822 const Eigen::MatrixBase<Matrix6Like> & I,
823 const bool update_I)
const
825 data.U = I.col(Inertia::ANGULAR +
axis);
827 Scalar(1) / (I(Inertia::ANGULAR +
axis, Inertia::ANGULAR +
axis) + armature[0]);
836 return std::string(
"JointModelR") + axisLabel<axis>();
848 return Vector3::UnitX();
850 return Vector3::UnitY();
852 return Vector3::UnitZ();
854 assert(
false &&
"must never happen");
860 template<
typename NewScalar>
885 #include <boost/type_traits.hpp>
889 template<
typename Scalar,
int Options,
int axis>
891 :
public integral_constant<bool, true>
895 template<
typename Scalar,
int Options,
int axis>
897 :
public integral_constant<bool, true>
901 template<
typename Scalar,
int Options,
int axis>
903 :
public integral_constant<bool, true>
907 template<
typename Scalar,
int Options,
int axis>
909 :
public integral_constant<bool, true>
914 #endif // ifndef __pinocchio_multibody_joint_revolute_hpp__
JointRevoluteTpl< _Scalar, _Options, axis > JointDerived
static ReturnType run(const Inertia &Y, const Constraint &)
DenseBase matrix_impl() const
JointDataTpl< Scalar, Options, JointCollectionTpl >::ConfigVector_t joint_q(const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata)
Visit a JointDataVariant through JointConfigVisitor to get the joint configuration vector.
#define PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
EIGEN_DONT_INLINE void calc(JointDataDerived &data, const Blank, const typename Eigen::MatrixBase< TangentVector > &vs) const
Forward declaration of the multiplication operation return type. Should be overloaded,...
Eigen::Matrix< Scalar, NQ, 1, Options > ConfigVector_t
JointModelBase< JointModelRevoluteTpl > Base
static std::string classname()
TransposeConst transpose() const
MotionRevoluteTpl __mult__(const OtherScalar &alpha) const
Eigen::Matrix< Scalar, 6, 1, Options > Vector6
const std::vector< bool > hasConfigurationLimit() const
static void cross(const Eigen::MatrixBase< V3_in > &vin, const Eigen::MatrixBase< V3_out > &vout)
MotionAlgebraAction< JointMotionSubspaceRevoluteTpl, MotionDerived >::ReturnType motionAction(const MotionDense< MotionDerived > &m) const
SpatialAxis< axis+ANGULAR > Axis
JointRevoluteTpl< context::Scalar, context::Options, 0 > JointRX
int idx_q(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxQVisitor to get the index in the full model configuration space...
static std::string classname()
JointRevoluteTpl< context::Scalar, context::Options, 2 > JointRZ
JointMotionSubspaceRevoluteTpl< S2, O2, 2 > Constraint
const std::vector< bool > hasConfigurationLimitInTangent() const
PlainReturnType plain() const
InertiaTpl< S1, O1 > Inertia
M6Like::ConstColXpr ReturnType
ReducedSquaredMatrix::IdentityReturnType StDiagonalMatrixSOperationReturnType
Return type of the Constraint::Transpose * Force operation.
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...
Eigen::Matrix< Scalar, 6, 1, Options > ReturnType
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_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
Eigen::Matrix< Scalar, 6, 1, Options > ReturnType
Eigen::MatrixBase< ForceSet >::ConstRowXpr ReturnType
static ReturnType run(const Inertia &Y, const Constraint &)
MultiplicationOp< Eigen::MatrixBase< M6Like >, Constraint >::ReturnType ReturnType
JointModelRevoluteTpl< Scalar, Options, axis > JointModelDerived
PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like) operator*(const Eigen
JointDataRevoluteTpl< context::Scalar, context::Options, 0 > JointDataRX
JointModelRevoluteTpl< context::Scalar, context::Options, 0 > JointModelRX
ConstraintForceOp< JointMotionSubspaceRevoluteTpl, ForceDerived >::ReturnType operator*(const ForceDense< ForceDerived > &f) const
const Scalar & angularRate() const
Eigen::Matrix< Scalar, 4, 4, Options > Matrix4
EIGEN_STRONG_INLINE void motionAction(const MotionDense< M1 > &v, MotionDense< M2 > &mout) const
Matrix4 HomogeneousMatrixType
MotionDerived::MotionPlain operator+(const MotionHelicalUnalignedTpl< S1, O1 > &m1, const MotionDense< MotionDerived > &m2)
JointDataRevoluteTpl< Scalar, Options, axis > JointDataDerived
#define PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(Joint)
ReturnTypeNotDefined ReturnType
JointRevoluteTpl< _Scalar, _Options, axis > JointDerived
Eigen::Matrix< Scalar, 6, NV, Options > U_t
std::string shortname() const
JointDataDerived createData() const
void calc_aba(JointDataDerived &data, const Eigen::MatrixBase< VectorLike > &armature, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const
void SINCOS(const S1 &a, S2 *sa, S3 *ca)
Computes sin/cos values of a given input scalar.
MotionTpl< Scalar, Options > ReturnType
Return type of the ation of a Motion onto an object of type D.
InertiaTpl< S1, O1 > Inertia
Vector3 getMotionAxis() const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW MOTION_TYPEDEF_TPL(MotionRevoluteTpl)
MotionRevoluteTpl(const Eigen::MatrixBase< Vector1Like > &v)
ConstLinearType linear() const
#define PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR
JointModelRevoluteTpl< context::Scalar, context::Options, 1 > JointModelRY
EIGEN_DONT_INLINE void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs, const typename Eigen::MatrixBase< TangentVector > &vs) const
Symmetric3Tpl< Scalar, Options > Symmetric3
JointDataRevoluteTpl< context::Scalar, context::Options, 2 > JointDataRZ
PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR ConfigVector_t joint_q
ConstraintForceSetOp< JointMotionSubspaceRevoluteTpl, Derived >::ReturnType operator*(const Eigen::MatrixBase< Derived > &F) const
[CRBA] MatrixBase operator* (Constraint::Transpose S, ForceSet::Block)
ReturnTypeNotDefined ReturnType
void se3Action_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
JointMotionSubspaceRevoluteTpl< S2, O2, 0 > Constraint
Axis::CartesianAxis3 CartesianAxis3
JointDataRevoluteTpl< context::Scalar, context::Options, 1 > JointDataRY
MotionTpl< Scalar, Options > ReturnType
Eigen::Matrix< Scalar, NV, NV, Options > D_t
MotionPlain motionAction(const MotionDense< M1 > &v) const
JointDataTpl< Scalar, Options, JointCollectionTpl >::TangentVector_t joint_v(const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata)
Visit a JointDataVariant through JointConfigVisitor to get the joint velocity vector.
JointRevoluteTpl< context::Scalar, context::Options, 1 > JointRY
EIGEN_DONT_INLINE void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs) const
MotionPlain PlainReturnType
MotionRevoluteTpl< Scalar, Options, axis > JointMotion
SpatialAxis< ANGULAR+axis > Axis
SE3GroupAction< JointMotionSubspaceRevoluteTpl >::ReturnType se3ActionInverse(const SE3Tpl< S1, O1 > &m) const
JointModelRevoluteTpl< context::Scalar, context::Options, 2 > JointModelRZ
void calc(const ConstraintModelTpl< Scalar, Options, ConstraintCollectionTpl > &cmodel, ConstraintDataTpl< Scalar, Options, ConstraintCollectionTpl > &cdata, const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data)
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
const JointMotionSubspaceRevoluteTpl & ref
Eigen::Matrix< Scalar, 1, 1, Options > JointForce
SE3GroupAction< JointMotionSubspaceRevoluteTpl >::ReturnType se3Action(const SE3Tpl< S1, O1 > &m) const
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...
MotionTpl< Scalar, Options > MotionPlain
JointMotionSubspaceRevoluteTpl< S2, O2, 1 > Constraint
#define PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(Joint)
MotionRevoluteTpl(const Scalar &w)
Eigen::Matrix< Scalar, NV, 1, Options > TangentVector_t
bool isEqual_impl(const MotionRevoluteTpl &other) const
bool isEqual(const JointMotionSubspaceRevoluteTpl &) const
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
TransformRevoluteTpl< Scalar, Options, axis > Transformation_t
bool comparison_eq(const LhsType &lhs_value, const RhsType &rhs_value)
Return type of the Constraint::Transpose * ForceSet operation.
ForceDense< ForceDerived >::ConstAngularType::template ConstFixedSegmentReturnType< 1 >::Type ReturnType
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointRevoluteTpl< _Scalar, _Options, axis > JointDerived
Base class for rigid transformation.
JointMotionSubspaceRevoluteTpl()
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointRevoluteTpl< _Scalar, _Options, axis > JointDerived
const typedef Vector3 ConstLinearType
MotionRevoluteTpl< Scalar, Options, axis > Motion_t
MultiplicationOp< Inertia, Constraint >::ReturnType ReturnType
JointMotionSubspaceRevoluteTpl< Scalar, Options, axis > Constraint_t
Eigen::Matrix< Scalar, 6, 1, Options > DenseBase
EIGEN_STRONG_INLINE MotionDerived::MotionPlain operator^(const MotionDense< MotionDerived > &m1, const MotionHelicalUnalignedTpl< S2, O2 > &m2)
MotionPlain se3Action_impl(const SE3Tpl< S2, O2 > &m) const
InertiaTpl< S1, O1 > Inertia
JointMotionSubspaceRevoluteTpl< Scalar, Options, axis > Constraint
#define PINOCCHIO_CONSTRAINT_TYPEDEF_TPL(DERIVED)
TransposeConst(const JointMotionSubspaceRevoluteTpl &ref)
const typedef Vector3 ConstAngularType
static ReturnType run(const Eigen::MatrixBase< M6Like > &Y, const Constraint &)
Eigen::Matrix< S2, 6, 1, O2 > ReturnType
MotionPlain se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m) const
Common traits structure to fully define base classes for CRTP.
MotionZeroTpl< Scalar, Options > Bias_t
MultiplicationOp< Inertia, Constraint >::ReturnType ReturnType
void se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
Eigen::Matrix< Scalar, 1, 1, Options > ReducedSquaredMatrix
void setTo(MotionDense< MotionDerived > &m) const
#define PINOCCHIO_EIGEN_REF_TYPE(D)
DenseBase MatrixReturnType
std::string shortname() const
static ReturnType run(const Inertia &Y, const Constraint &)
Type of the cast of a class C templated by Scalar and Options, to a new NewScalar type....
Eigen::Matrix< Scalar, 6, NV, Options > UD_t
MultiplicationOp< Inertia, Constraint >::ReturnType ReturnType
Eigen::Matrix< Scalar, 6, 6, Options > Matrix6
JointMotion __mult__(const Eigen::MatrixBase< Vector1Like > &v) const
void addTo(MotionDense< MotionDerived > &v) const
ConstAngularType angular() const
Eigen::Matrix< Scalar, 3, 1, _Options > Vector3
JointModelRevoluteTpl< NewScalar, Options, axis > type
static void alphaCross(const Scalar &s, const Eigen::MatrixBase< V3_in > &vin, const Eigen::MatrixBase< V3_out > &vout)
Main pinocchio namespace.
JointModelRevoluteTpl< NewScalar, Options, axis > cast() const
const typedef DenseBase ConstMatrixReturnType
pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:46