Go to the documentation of this file.
5 #ifndef __pinocchio_multibody_joint_mimic_hpp__
6 #define __pinocchio_multibody_joint_mimic_hpp__
14 template<
class Constra
int>
17 template<
class Constra
int>
41 template<
class Constra
int>
47 template<
class Constra
int,
typename MotionDerived>
53 template<
class Constra
int,
typename ForceDerived>
60 typedef Eigen::Matrix<
62 IdealReturnType::RowsAtCompileTime,
63 IdealReturnType::ColsAtCompileTime,
68 template<
class Constra
int,
typename ForceSet>
74 typedef Eigen::Matrix<
77 ForceSet::ColsAtCompileTime,
82 template<
class Constra
int>
85 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
125 template<
typename VectorLike>
126 JointMotion
__mult__(
const Eigen::MatrixBase<VectorLike> &
v)
const
128 assert(
v.size() ==
nv());
133 template<
typename S1,
int O1>
140 template<
typename S1,
int O1>
160 template<
typename Derived>
172 template<
typename Derived>
194 template<
typename MotionDerived>
235 template<
typename ParentConstra
int>
250 template<
typename S1,
int O1,
typename _Constra
int>
265 template<
typename S1,
int O1,
typename _Constra
int>
279 template<
typename M6Like,
typename _Constra
int>
289 template<
typename M6Like,
typename _Constra
int>
297 run(
const Eigen::MatrixBase<M6Like> & Y,
const Constraint & scaled_constraint)
304 template<
class Jo
int>
306 template<
class Jo
intModel>
308 template<
class Jo
intData>
311 template<
class Jo
int>
347 template<
class Jo
int>
354 template<
class Jo
int>
361 template<
class Jo
intData>
364 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
373 ,
joint_q(ConfigVector_t::Zero())
374 ,
joint_v(TangentVector_t::Zero())
511 template<
class Jo
intModel>
565 template<
typename NewScalar,
typename Jo
intModel>
572 template<
class Jo
intModel>
575 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
603 return *
static_cast<Base *
>(
this);
607 return *
static_cast<const Base *
>(
this);
650 template<
typename ConfigVector>
651 EIGEN_DONT_INLINE
void
652 calc(JointDataDerived & jdata,
const typename Eigen::MatrixBase<ConfigVector> &
qs)
const
660 template<
typename TangentVector>
662 JointDataDerived & jdata,
664 const typename Eigen::MatrixBase<TangentVector> & vs)
const
670 template<
typename ConfigVector,
typename TangentVector>
672 JointDataDerived & jdata,
673 const typename Eigen::MatrixBase<ConfigVector> &
qs,
674 const typename Eigen::MatrixBase<TangentVector> & vs)
const
683 template<
typename VectorLike,
typename Matrix6Like>
685 JointDataDerived &
data,
686 const Eigen::MatrixBase<VectorLike> & armature,
687 const Eigen::MatrixBase<Matrix6Like> & I,
688 const bool update_I)
const
707 template<
typename NewScalar>
714 pinocchio::cast<NewScalar>(
m_offset));
846 #endif // ifndef __pinocchio_multibody_joint_mimic_hpp__
traits< Constraint >::JointMotion JointMotion
JointDataDerived createData() const
#define PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
bool isEqual(const ScaledJointMotionSubspace &other) const
const Scalar & scaling() const
traits< Joint >::ConfigVector_t ConfigVector_t
Forward declaration of the multiplication operation return type. Should be overloaded,...
Constraint::Scalar Scalar
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef traits< JointModelMimic >::JointDerived JointDerived
OriginalReturnType ReturnType
const std::vector< bool > hasConfigurationLimitInTangent() const
InertiaTpl< S1, O1 > Inertia
SizeDepType< NV >::template BlockReturn< D >::ConstType jointBlock_impl(const Eigen::MatrixBase< D > &Mat) const
Returns a block of dimension nv()xnv() located at position idx_v(),idx_v() in the matrix Mat.
SizeDepType< NQ >::template SegmentReturn< D >::ConstType jointConfigSelector_impl(const Eigen::MatrixBase< D > &a) const
static ReturnType run(const Inertia &Y, const Constraint &scaled_constraint)
JointDataMimic(const JointDataMimic &other)
bool isEqual(const JointDataBase< Derived > &other) const
 
traits< Joint >::JointDataDerived JointDataBase
traits< Constraint >::Scalar Scalar
UTypeConstRef U_accessor() const
traits< Constraint >::MatrixReturnType MatrixReturnType
const Scalar & scaling() const
int idx_q(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxQVisitor to get the index in the full model configuration space...
SE3GroupAction< Constraint >::ReturnType SE3ActionReturnType
traits< Constraint >::ConstMatrixReturnType ConstMatrixReturnType
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...
static ColsReturn< D >::ConstType middleCols(const Eigen::MatrixBase< D > &mat, typename Eigen::DenseBase< D >::Index start, typename Eigen::DenseBase< D >::Index size=NV)
const std::vector< bool > hasConfigurationLimitInTangent() const
JointModelMimic< JointModelNewType > type
ScaledJointMotionSubspace()
int nv(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointNvVisitor to get the dimension of the joint tangent space.
traits< Joint >::JointModelDerived JointModelBase
TangentVectorTypeRef joint_v_accessor()
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.
JointModelBase< JointModelMimic > Base
static std::string classname()
ScaledJointMotionSubspace(const Scalar &scaling_factor)
SizeDepType< NV >::template RowsReturn< D >::ConstType jointRows_impl(const Eigen::MatrixBase< D > &A) const
bool isEqual(const JointDataMimic &other) const
static ReturnType run(const JointMotionSubspaceBase< Constraint > &constraint)
ConstraintTypeRef S_accessor()
MultiplicationOp< Inertia, Constraint >::ReturnType ReturnType
Constraint & constraint()
static ReturnType run(const Eigen::MatrixBase< M6Like > &Y, const Constraint &scaled_constraint)
ScaledJointMotionSubspace(const ScaledJointMotionSubspace &other)
ConstraintForceSetOp< ScaledJointMotionSubspace, Derived >::ReturnType operator*(const Eigen::MatrixBase< Derived > &F) const
[CRBA] MatrixBase operator* (Constraint::Transpose S, ForceSet::Block)
SizeDepType< NV >::template ColsReturn< D >::ConstType jointCols_impl(const Eigen::MatrixBase< D > &A) const
const std::vector< bool > hasConfigurationLimit() const
TransposeConst transpose() const
void setIndexes_impl(JointIndex id, int, int)
ScaledJointMotionSubspace(const Constraint &constraint, const Scalar &scaling_factor)
traits< Constraint >::StDiagonalMatrixSOperationReturnType ReturnType
ReturnTypeNotDefined ReturnType
void setIndexes(JointIndex id, int q, int v)
const Scalar & offset() const
const Base & base() const
BiasTypeConstRef c_accessor() const
ScaledJointMotionSubspace< _Constraint > Constraint
ConfigVectorTypeConstRef joint_q_accessor() const
ScaledJointMotionSubspace< _Constraint > Constraint
Return type of the ation of a Motion onto an object of type D.
traits< Joint >::Transformation_t Transformation_t
JointMotion __mult__(const Eigen::MatrixBase< VectorLike > &v) const
traits< JointDerived >::Scalar Scalar
ConstraintForceOp< Constraint, ForceDerived >::ReturnType OriginalReturnType
Eigen::Matrix< Scalar, IdealReturnType::RowsAtCompileTime, IdealReturnType::ColsAtCompileTime, Constraint::Options > ReturnType
SE3GroupAction< Constraint >::ReturnType ReturnType
SE3ActionReturnType se3Action(const SE3Tpl< S1, O1 > &m) const
traits< Joint >::UD_t UD_t
static std::string classname()
traits< Joint >::TangentVector_t TangentVector_t
MotionTypeRef v_accessor()
MultiplicationOp< Eigen::MatrixBase< M6Like >, Constraint >::ReturnType ReturnType
const ScaledJointMotionSubspace & ref
TangentVector_t & jointVelocity()
void calc_aba(JointDataDerived &data, const Eigen::MatrixBase< VectorLike > &armature, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const
MotionAlgebraAction< ScaledJointMotionSubspace, MotionDerived >::ReturnType motionAction(const MotionDense< MotionDerived > &m) const
traits< JointDerived >::Scalar Scalar
ConstraintTypeConstRef S_accessor() const
JointMotionSubspaceBase< ScaledJointMotionSubspace > Base
traits< Constraint >::JointForce JointForce
EIGEN_DONT_INLINE void calc(JointDataDerived &jdata, const typename Eigen::MatrixBase< ConfigVector > &qs, const typename Eigen::MatrixBase< TangentVector > &vs) const
ReturnTypeNotDefined ReturnType
DTypeConstRef StU_accessor() const
Constraint::Scalar Scalar
Constraint::Scalar Scalar
InertiaTpl< S1, O1 > Inertia
SizeDepType< NV >::template RowsReturn< D >::Type jointRows_impl(Eigen::MatrixBase< D > &A) const
DTypeConstRef Dinv_accessor() const
JointMimic< typename traits< Joint >::JointDerived > JointDerived
JointDataDerived createData() const
ScalarMatrixProduct< Scalar, OriginalReturnType >::type IdealReturnType
traits< Joint >::Motion_t Motion_t
CastType< NewScalar, JointModelMimic >::type cast() const
static std::string classname()
const JointData & jdata() const
SizeDepType< NV >::template SegmentReturn< D >::Type jointVelocitySelector_impl(Eigen::MatrixBase< D > &a) const
const Constraint & constraint() const
JointDataMimic & operator=(const JointDataMimic &other)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Derived & derived()
MotionAlgebraAction< Constraint, MotionDerived >::ReturnType ReturnType
ConstraintForceSetOp< Constraint, ForceSet >::ReturnType OriginalReturnType
JointModelMimic< JointModelBase > JointModelDerived
TangentVectorTypeConstRef joint_v_accessor() const
static RowsReturn< D >::ConstType middleRows(const Eigen::MatrixBase< D > &mat, typename Eigen::DenseBase< D >::Index start, typename Eigen::DenseBase< D >::Index size=NV)
ScaledJointMotionSubspace< ParentConstraint > Constraint
traits< Joint >::Bias_t Bias_t
ScalarMatrixProduct< Scalar, OriginalReturnType >::type IdealReturnType
static SegmentReturn< D >::ConstType segment(const Eigen::MatrixBase< D > &mat, typename Eigen::DenseBase< D >::Index start, typename Eigen::DenseBase< D >::Index size=NV)
PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(JointDerived)
ConfigVectorTypeRef joint_q_accessor()
traits< Constraint >::DenseBase DenseBase
traits< Joint >::Scalar Scalar
const TangentVector_t & jointVelocity() const
ReducedSquaredMatrix StDiagonalMatrixSOperationReturnType
ScaledJointMotionSubspace< typename traits< Joint >::Constraint_t > Constraint_t
SizeDepType< NV >::template SegmentReturn< D >::ConstType jointVelocitySelector_impl(const Eigen::MatrixBase< D > &a) const
CastType< NewScalar, JointModel >::type JointModelNewType
SizeDepType< NQ >::template SegmentReturn< D >::Type jointConfigSelector_impl(Eigen::MatrixBase< D > &a) const
const JointModel & jmodel() const
ScaledJointMotionSubspace & operator=(const ScaledJointMotionSubspace &other)
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.
JointMimic< typename traits< Joint >::JointDerived > JointDerived
EIGEN_DONT_INLINE void calc(JointDataDerived &jdata, const typename Eigen::MatrixBase< ConfigVector > &qs) const
UDTypeRef UDinv_accessor()
MultiplicationOp< Inertia, _Constraint >::ReturnType OriginalReturnType
static std::string classname()
TansformTypeRef M_accessor()
DenseBase matrix_impl() const
ScaledJointMotionSubspace< _Constraint > Constraint
PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(JointDerived)
TangentVector_t joint_v
Transform velocity vector.
UDTypeConstRef UDinv_accessor() const
std::string shortname() const
TansformTypeConstRef M_accessor() const
ConstraintForceOp< ScaledJointMotionSubspace, Derived >::ReturnType operator*(const ForceDense< Derived > &f) const
SizeDepType< NV >::template ColsReturn< D >::Type jointCols_impl(Eigen::MatrixBase< D > &A) const
const std::vector< bool > hasConfigurationLimit() const
EIGEN_DONT_INLINE void calc(JointDataDerived &jdata, const Blank blank, const typename Eigen::MatrixBase< TangentVector > &vs) const
TransposeConst(const ScaledJointMotionSubspace &ref)
#define PINOCCHIO_CONSTRAINT_TYPEDEF_TPL(DERIVED)
SE3ActionReturnType se3ActionInverse(const SE3Tpl< S1, O1 > &m) const
Common traits structure to fully define base classes for CRTP.
MotionTypeConstRef v_accessor() 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.
Eigen::Matrix< Scalar, Constraint::NV, ForceSet::ColsAtCompileTime, Constraint::Options|Eigen::RowMajor > ReturnType
static BlockReturn< D >::ConstType block(const Eigen::MatrixBase< D > &mat, typename Eigen::DenseBase< D >::Index row_id, typename Eigen::DenseBase< D >::Index col_id, typename Eigen::DenseBase< D >::Index row_size_block=NV, typename Eigen::DenseBase< D >::Index col_size_block=NV)
Type of the cast of a class C templated by Scalar and Options, to a new NewScalar type....
traits< Constraint >::ReducedSquaredMatrix ReducedSquaredMatrix
std::string shortname() const
std::string shortname() const
Transformation_t M() const
SizeDepType< NV >::template BlockReturn< D >::Type jointBlock_impl(Eigen::MatrixBase< D > &Mat) const
JointDataMimic(const JointDataBase< JointData > &jdata, const Scalar &scaling)
ConfigVector_t & jointConfiguration()
void calc_aba(JointDataDerived &data, const Eigen::MatrixBase< VectorLike > &armature, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const
MultiplicationOp< Inertia, _Constraint >::ReturnType OriginalReturnType
JointModelMimic(const JointModelBase< JointModel > &jmodel, const Scalar &scaling, const Scalar &offset)
const Scalar & scaling() const
ConfigVector_t joint_q
Transform configuration vector.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef traits< JointDataMimic >::JointDerived JointDerived
std::string shortname() const
const ConfigVector_t & jointConfiguration() const
Main pinocchio namespace.
JointDataMimic< JointDataBase > JointDataDerived
void calc(JointDataDerived &data, const Eigen::MatrixBase< ConfigVector > &q) const
JointDataBase< JointDataMimic< JointData > > Base
pinocchio
Author(s):
autogenerated on Sun Nov 10 2024 03:42:59