Go to the documentation of this file.
6 #ifndef __pinocchio_multibody_joint_prismatic_unaligned_hpp__
7 #define __pinocchio_multibody_joint_prismatic_unaligned_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 MotionPrismaticUnalignedTpl : MotionBase<MotionPrismaticUnalignedTpl<_Scalar, _Options>>
67 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
74 template<
typename Vector3Like,
typename S2>
79 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3);
82 inline PlainReturnType
plain()
const
84 return PlainReturnType(
m_axis *
m_v, PlainReturnType::Vector3::Zero());
87 template<
typename OtherScalar>
93 template<
typename Derived>
99 template<
typename Derived>
106 template<
typename S2,
int O2,
typename D2>
109 v.linear().noalias() =
m_v * (
m.rotation() *
m_axis);
110 v.angular().setZero();
113 template<
typename S2,
int O2>
121 template<
typename S2,
int O2,
typename D2>
125 v.linear().noalias() =
m_v * (
m.rotation().transpose() *
m_axis);
128 v.angular().setZero();
131 template<
typename S2,
int O2>
139 template<
typename M1,
typename M2>
150 template<
typename M1>
187 template<
typename Scalar,
int Options,
typename MotionDerived>
191 typedef typename MotionDerived::MotionPlain ReturnType;
192 return ReturnType(m1.linearRate() * m1.axis() + m2.
linear(), m2.
angular());
195 template<
typename MotionDerived,
typename S2,
int O2>
196 inline typename MotionDerived::MotionPlain
199 return m2.motionAction(m1);
202 template<
typename Scalar,
int Options>
205 template<
typename _Scalar,
int _Options>
223 typedef Eigen::Matrix<Scalar, 3, 1, Options>
Vector3;
231 template<
typename Scalar,
int Options>
237 template<
typename Scalar,
int Options,
typename MotionDerived>
245 template<
typename Scalar,
int Options,
typename ForceDerived>
250 typedef Eigen::Matrix<
259 template<
typename Scalar,
int Options,
typename ForceSet>
265 Eigen::Transpose<const Vector3>,
266 typename Eigen::MatrixBase<const ForceSet>::template NRowsBlockXpr<3>::Type>
::type ReturnType;
269 template<
typename _Scalar,
int _Options>
273 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
287 template<
typename Vector3Like>
291 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3);
294 template<
typename Vector1Like>
295 JointMotion
__mult__(
const Eigen::MatrixBase<Vector1Like> &
v)
const
297 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector1Like, 1);
298 return JointMotion(
m_axis,
v[0]);
301 template<
typename S1,
int O1>
307 v.linear().noalias() =
m.rotation() *
m_axis;
308 v.angular().setZero();
312 template<
typename S1,
int O1>
318 v.linear().noalias() =
m.rotation().transpose() *
m_axis;
319 v.angular().setZero();
337 template<
typename ForceDerived>
349 template<
typename ForceSet>
354 ForceSet::RowsAtCompileTime == 6, THIS_METHOD_IS_ONLY_FOR_MATRICES_OF_A_SPECIFIC_SIZE)
356 return ref.
axis().transpose() * F.template middleRows<3>(LINEAR);
374 S.template segment<3>(LINEAR) =
m_axis;
375 S.template segment<3>(ANGULAR).setZero();
379 template<
typename MotionDerived>
383 res.template segment<3>(LINEAR).noalias() =
v.angular().cross(
m_axis);
384 res.template segment<3>(ANGULAR).setZero();
408 template<
typename S1,
int O1,
typename S2,
int O2>
417 template<
typename S1,
int O1,
typename S2,
int O2>
428 const S1 &
m =
Y.mass();
431 res.template segment<3>(Constraint::LINEAR).noalias() =
m * cpu.
axis();
432 res.template segment<3>(Constraint::ANGULAR).noalias() =
433 c.cross(
res.template segment<3>(Constraint::LINEAR));
440 template<
typename M6Like,
typename Scalar,
int Options>
442 Eigen::MatrixBase<M6Like>,
456 template<
typename M6Like,
typename Scalar,
int Options>
458 Eigen::MatrixBase<M6Like>,
466 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(M6Like, 6, 6);
467 return Y.derived().template middleCols<3>(Constraint::LINEAR) * cru.
axis();
472 template<
typename Scalar,
int Options>
475 template<
typename _Scalar,
int _Options>
496 typedef Eigen::Matrix<Scalar, 6, NV, Options>
U_t;
497 typedef Eigen::Matrix<Scalar, NV, NV, Options>
D_t;
498 typedef Eigen::Matrix<Scalar, 6, NV, Options>
UD_t;
506 template<
typename _Scalar,
int _Options>
513 template<
typename _Scalar,
int _Options>
515 :
public JointDataBase<JointDataPrismaticUnalignedTpl<_Scalar, _Options>>
517 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
537 :
joint_q(ConfigVector_t::Zero())
538 ,
joint_v(TangentVector_t::Zero())
539 ,
M(Transformation_t::
Vector3::Zero())
544 ,
UDinv(UD_t::Zero())
549 template<
typename Vector3Like>
551 :
joint_q(ConfigVector_t::Zero())
552 ,
joint_v(TangentVector_t::Zero())
553 ,
M(Transformation_t::
Vector3::Zero())
558 ,
UDinv(UD_t::Zero())
565 return std::string(
"JointDataPrismaticUnaligned");
574 template<
typename _Scalar,
int _Options>
582 template<
typename _Scalar,
int _Options>
584 :
public JointModelBase<JointModelPrismaticUnalignedTpl<_Scalar, _Options>>
586 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
596 typedef Eigen::Matrix<Scalar, 3, 1, _Options>
Vector3;
606 assert(
isUnitary(
axis) &&
"Translation axis is not unitary");
609 template<
typename Vector3Like>
613 EIGEN_STATIC_ASSERT_VECTOR_ONLY(Vector3Like);
614 assert(
isUnitary(
axis) &&
"Translation axis is not unitary");
619 return JointDataDerived(
axis);
638 template<
typename ConfigVector>
639 void calc(JointDataDerived &
data,
const typename Eigen::MatrixBase<ConfigVector> &
qs)
const
642 data.M.translation().noalias() =
axis *
data.joint_q[0];
645 template<
typename TangentVector>
647 calc(JointDataDerived &
data,
const Blank,
const typename Eigen::MatrixBase<TangentVector> & vs)
651 data.v.linearRate() =
data.joint_v[0];
654 template<
typename ConfigVector,
typename TangentVector>
656 JointDataDerived &
data,
657 const typename Eigen::MatrixBase<ConfigVector> &
qs,
658 const typename Eigen::MatrixBase<TangentVector> & vs)
const
663 data.v.linearRate() =
data.joint_v[0];
666 template<
typename VectorLike,
typename Matrix6Like>
668 JointDataDerived &
data,
669 const Eigen::MatrixBase<VectorLike> & armature,
670 const Eigen::MatrixBase<Matrix6Like> & I,
671 const bool update_I)
const
673 data.U.noalias() = I.template block<6, 3>(0, Inertia::LINEAR) *
axis;
675 Scalar(1) / (
axis.dot(
data.U.template segment<3>(Inertia::LINEAR)) + armature[0]);
684 return std::string(
"JointModelPrismaticUnaligned");
692 template<
typename NewScalar>
696 ReturnType
res(
axis.template cast<NewScalar>());
711 #include <boost/type_traits.hpp>
715 template<
typename Scalar,
int Options>
717 :
public integral_constant<bool, true>
721 template<
typename Scalar,
int Options>
723 :
public integral_constant<bool, true>
727 template<
typename Scalar,
int Options>
729 :
public integral_constant<bool, true>
733 template<
typename Scalar,
int Options>
735 :
public integral_constant<bool, true>
740 #endif // ifndef __pinocchio_multibody_joint_prismatic_unaligned_hpp__
ConstraintForceOp< JointMotionSubspacePrismaticUnalignedTpl, ForceDerived >::ReturnType operator*(const ForceDense< ForceDerived > &f) const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointPrismaticUnalignedTpl< _Scalar, _Options > JointDerived
PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR ConfigVector_t joint_q
JointMotionSubspacePrismaticUnalignedTpl(const Eigen::MatrixBase< Vector3Like > &axis)
Eigen::Matrix< Scalar, 6, 6, Options > Matrix6
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs) const
#define PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
ConstraintForceSetOp< JointMotionSubspacePrismaticUnalignedTpl, ForceSet >::ReturnType operator*(const Eigen::MatrixBase< ForceSet > &F)
Forward declaration of the multiplication operation return type. Should be overloaded,...
const typedef MatrixMatrixProduct< M6LikeColsNonConst, Vector3 >::type ReturnType
Eigen::Matrix< Scalar, 6, 1, Options > ReturnType
std::string shortname() const
#define PINOCCHIO_EIGEN_DOT_PRODUCT_RETURN_TYPE(D1, D2)
Macro giving access to the return type of the dot product operation.
Eigen::Matrix< typename PINOCCHIO_EIGEN_DOT_PRODUCT_RETURN_TYPE(Vector3, typename ForceDense< ForceDerived >::ConstAngularType), 1, 1, Options > ReturnType
JointModelPrismaticUnalignedTpl()
Eigen::Matrix< Scalar, 1, 1, Options > ReducedSquaredMatrix
MotionPlain motionAction(const MotionDense< M1 > &v) const
Eigen::Matrix< Scalar, 6, NV, Options > UD_t
std::string shortname() const
bool isUnitary(const Eigen::MatrixBase< MatrixLike > &mat, const typename MatrixLike::RealScalar &prec=Eigen::NumTraits< typename MatrixLike::Scalar >::dummy_precision())
Check whether the input matrix is Unitary within the given precision.
int idx_q(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxQVisitor to get the index in the full model configuration space...
traits< JointMotionSubspacePrismaticUnalignedTpl< Scalar, Options > >::Vector3 Vector3
SE3GroupAction< JointMotionSubspacePrismaticUnalignedTpl >::ReturnType se3ActionInverse(const SE3Tpl< S1, O1 > &m) const
JointMotionSubspacePrismaticUnalignedTpl< Scalar, Options > Constraint
const std::vector< bool > hasConfigurationLimitInTangent() const
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, 3, 1, Options > Vector3
DenseBase MatrixReturnType
bool isEqual(const JointMotionSubspacePrismaticUnalignedTpl &other) const
MotionPrismaticUnalignedTpl< Scalar, Options > JointMotion
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
JointModelPrismaticUnalignedTpl(const Eigen::MatrixBase< Vector3Like > &axis)
const typedef DenseBase ConstMatrixReturnType
PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like) operator*(const Eigen
MultiplicationOp< Eigen::MatrixBase< M6Like >, Constraint >::ReturnType ReturnType
JointModelPrismaticUnalignedTpl(const Scalar &x, const Scalar &y, const Scalar &z)
const Vector3 & axis() const
MotionDerived::MotionPlain operator+(const MotionHelicalUnalignedTpl< S1, O1 > &m1, const MotionDense< MotionDerived > &m2)
ReturnTypeNotDefined ReturnType
Eigen::Matrix< Scalar, NV, 1, Options > TangentVector_t
void setIndexes(JointIndex id, int q, int v)
const Scalar & linearRate() const
MotionPrismaticUnalignedTpl(const Eigen::MatrixBase< Vector3Like > &axis, const S2 &v)
Eigen::Matrix< Scalar, 1, 1, Options > JointForce
JointMotionSubspacePrismaticUnalignedTpl< Scalar, Options > Constraint
const std::vector< bool > hasConfigurationLimit() const
Return type of the ation of a Motion onto an object of type D.
void addTo(MotionDense< Derived > &other) const
MotionPrismaticUnalignedTpl __mult__(const OtherScalar &alpha) const
PlainReturnType plain() const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointPrismaticUnalignedTpl< _Scalar, _Options > JointDerived
void setTo(MotionDense< Derived > &other) const
Eigen::Matrix< Scalar, 6, 1, Options > ReturnType
ConstLinearType linear() const
void calc(JointDataDerived &data, const Blank, const typename Eigen::MatrixBase< TangentVector > &vs) const
static std::string classname()
#define PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR
MotionPrismaticUnalignedTpl()
JointPrismaticUnalignedTpl< _Scalar, _Options > JointDerived
TransformTranslationTpl< Scalar, Options > Transformation_t
MotionPlain se3Action_impl(const SE3Tpl< S2, O2 > &m) const
ReturnTypeNotDefined ReturnType
SE3GroupAction< JointMotionSubspacePrismaticUnalignedTpl >::ReturnType se3Action(const SE3Tpl< S1, O1 > &m) const
JointDataPrismaticUnalignedTpl< Scalar, Options > JointDataDerived
Eigen::Matrix< Scalar, 6, 1, Options > DenseBase
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION(JointModelFreeFlyerTpl)
Free-flyer joint in .
ReducedSquaredMatrix::IdentityReturnType StDiagonalMatrixSOperationReturnType
PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(JointDerived)
Eigen::Matrix< Scalar, 4, 4, Options > Matrix4
MultiplicationOp< Inertia, Constraint >::ReturnType ReturnType
Eigen::Matrix< S2, 6, 1, O2 > ReturnType
MotionPrismaticUnalignedTpl< context::Scalar > MotionPrismaticUnaligned
InertiaTpl< S1, O1 > Inertia
Eigen::Matrix< Scalar, NQ, 1, Options > ConfigVector_t
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
static std::string classname()
TransposeConst transpose() const
JointMotionSubspacePrismaticUnalignedTpl()
Eigen::internal::remove_const< M6LikeCols >::type M6LikeColsNonConst
traits< JointMotionSubspacePrismaticUnalignedTpl >::Vector3 Vector3
MotionTpl< Scalar, Options > ReturnType
MotionZeroTpl< Scalar, Options > Bias_t
JointMotion __mult__(const Eigen::MatrixBase< Vector1Like > &v) const
Eigen::Matrix< Scalar, 3, 1, _Options > Vector3
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
JointDataDerived createData() const
JointModelPrismaticUnalignedTpl< NewScalar, Options > cast() const
MotionTpl< Scalar, Options > MotionPlain
JointMotionSubspacePrismaticUnalignedTpl< Scalar, Options > Constraint_t
Matrix4 HomogeneousMatrixType
void se3Action_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
void calc_aba(JointDataDerived &data, const Eigen::MatrixBase< VectorLike > &armature, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const
static ReturnType run(const Eigen::MatrixBase< M6Like > &Y, const Constraint &cru)
Eigen::Matrix< Scalar, 6, 1, Options > Vector6
JointDataPrismaticUnalignedTpl(const Eigen::MatrixBase< Vector3Like > &axis)
Constraint::Vector3 Vector3
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
bool comparison_eq(const LhsType &lhs_value, const RhsType &rhs_value)
Return type of the Constraint::Transpose * ForceSet operation.
bool isEqual(const JointModelPrismaticUnalignedTpl &other) const
JointModelBase< JointModelPrismaticUnalignedTpl > Base
TransposeConst(const JointMotionSubspacePrismaticUnalignedTpl &ref)
JointModelPrismaticUnalignedTpl< Scalar, Options > JointModelDerived
MotionPlain PlainReturnType
MotionPlain se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m) const
MotionTpl< Scalar, Options > ReturnType
EIGEN_STRONG_INLINE MotionDerived::MotionPlain operator^(const MotionDense< MotionDerived > &m1, const MotionHelicalUnalignedTpl< S2, O2 > &m2)
void motionAction(const MotionDense< M1 > &v, MotionDense< M2 > &mout) const
JointMotionSubspacePrismaticUnalignedTpl< S2, O2 > Constraint
#define PINOCCHIO_CONSTRAINT_TYPEDEF_TPL(DERIVED)
MatrixMatrixProduct< Eigen::Transpose< const Vector3 >, typename Eigen::MatrixBase< const ForceSet >::template NRowsBlockXpr< 3 >::Type >::type ReturnType
Vector3 axis
3d main axis of the joint.
bool isEqual_impl(const MotionPrismaticUnalignedTpl &other) const
traits< JointMotionSubspacePrismaticUnalignedTpl< Scalar, Options > >::Vector3 Vector3
Common traits structure to fully define base classes for CRTP.
JointPrismaticUnalignedTpl< _Scalar, _Options > JointDerived
Eigen::Matrix< Scalar, 6, NV, Options > U_t
EIGEN_MAKE_ALIGNED_OPERATOR_NEW MOTION_TYPEDEF_TPL(MotionPrismaticUnalignedTpl)
MotionPrismaticUnalignedTpl< Scalar, Options > Motion_t
static ReturnType run(const Inertia &Y, const Constraint &cpu)
#define PINOCCHIO_EIGEN_REF_TYPE(D)
const typedef Vector3 ConstLinearType
Eigen::Matrix< Scalar, NV, NV, Options > D_t
PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(JointDerived)
const Vector3 & axis() const
DenseBase matrix_impl() const
SizeDepType< 3 >::ColsReturn< M6Like >::ConstType M6LikeCols
JointDataPrismaticUnalignedTpl()
void se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
bool isEqual(const JointModelBase< OtherDerived > &) const
DenseBase motionAction(const MotionDense< MotionDerived > &v) const
void normalize(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &qout)
Normalize a configuration vector.
const JointMotionSubspacePrismaticUnalignedTpl & ref
ConstAngularType angular() const
Main pinocchio namespace.
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs, const typename Eigen::MatrixBase< TangentVector > &vs) const
const typedef Vector3 ConstAngularType
pinocchio
Author(s):
autogenerated on Mon Dec 16 2024 03:41:03