Go to the documentation of this file.
6 #ifndef __pinocchio_multibody_joint_free_flyer_hpp__
7 #define __pinocchio_multibody_joint_free_flyer_hpp__
20 template<
typename Scalar,
int Options>
23 template<
typename _Scalar,
int _Options>
31 typedef Eigen::Matrix<Scalar, 6, 6, Options>
Matrix6;
39 typedef Eigen::Matrix<Scalar, 6, 6, Options>
DenseBase;
47 template<
typename _Scalar,
int _Options>
51 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
59 template<
typename Vector6Like>
60 JointMotion
__mult__(
const Eigen::MatrixBase<Vector6Like> & vj)
const
62 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector6Like, 6);
63 return JointMotion(vj);
66 template<
typename S1,
int O1>
69 return m.toActionMatrix();
72 template<
typename S1,
int O1>
75 return m.toActionMatrixInverse();
85 template<
typename Derived>
89 return phi.toVector();
93 template<
typename MatrixDerived>
95 operator*(
const Eigen::MatrixBase<MatrixDerived> & F)
107 return DenseBase::Identity();
110 template<
typename MotionDerived>
113 return v.toActionMatrix();
123 template<
typename Scalar,
int Options,
typename Vector6Like>
126 const Eigen::MatrixBase<Vector6Like> &
v)
128 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector6Like, 6);
135 template<
typename S1,
int O1,
typename S2,
int O2>
136 inline typename InertiaTpl<S1, O1>::Matrix6
143 template<
typename Matrix6Like,
typename S2,
int O2>
150 template<
typename S1,
int O1>
156 template<
typename S1,
int O1,
typename MotionDerived>
162 template<
typename Scalar,
int Options>
165 template<
typename _Scalar,
int _Options>
186 typedef Eigen::Matrix<Scalar, 6, NV, Options>
U_t;
187 typedef Eigen::Matrix<Scalar, NV, NV, Options>
D_t;
188 typedef Eigen::Matrix<Scalar, 6, NV, Options>
UD_t;
196 template<
typename _Scalar,
int _Options>
203 template<
typename _Scalar,
int _Options>
210 template<
typename _Scalar,
int _Options>
213 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
233 :
joint_q(ConfigVector_t::Zero())
234 ,
joint_v(TangentVector_t::Zero())
235 ,
M(Transformation_t::Identity())
236 ,
v(Motion_t::Zero())
239 ,
UDinv(UD_t::Identity())
247 return std::string(
"JointDataFreeFlyer");
281 template<
typename _Scalar,
int _Options>
282 struct JointModelFreeFlyerTpl :
public JointModelBase<JointModelFreeFlyerTpl<_Scalar, _Options>>
284 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
296 return JointDataDerived();
301 return {
true,
true,
true,
false,
false,
false,
false};
306 return {
true,
true,
true,
false,
false,
false};
309 template<
typename ConfigVectorLike>
311 Transformation_t & M,
const Eigen::MatrixBase<ConfigVectorLike> & q_joint)
const
313 EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(ConfigVector_t, ConfigVectorLike);
317 typedef Eigen::Map<const Quaternion> ConstQuaternionMap;
319 ConstQuaternionMap
quat(q_joint.template tail<4>().data());
322 assert(math::fabs(
static_cast<Scalar>(
quat.coeffs().squaredNorm() - 1)) <= 1e-4);
324 M.rotation(
quat.matrix());
325 M.translation(q_joint.template head<3>());
328 template<
typename Vector3Derived,
typename QuaternionDerived>
330 JointDataDerived &
data,
331 const typename Eigen::MatrixBase<Vector3Derived> & trans,
332 const typename Eigen::QuaternionBase<QuaternionDerived> & quat)
const
334 data.M.translation(trans);
338 template<
typename ConfigVector>
339 EIGEN_DONT_INLINE
void
340 calc(JointDataDerived &
data,
const typename Eigen::MatrixBase<ConfigVector> &
qs)
const
342 typedef typename Eigen::Quaternion<Scalar, Options>
Quaternion;
343 typedef Eigen::Map<const Quaternion> ConstQuaternionMap;
346 ConstQuaternionMap
quat(
data.joint_q.template tail<4>().data());
351 template<
typename TangentVector>
352 EIGEN_DONT_INLINE
void
353 calc(JointDataDerived &
data,
const Blank,
const typename Eigen::MatrixBase<TangentVector> & vs)
356 data.joint_v = vs.template segment<NV>(
idx_v());
360 template<
typename ConfigVector,
typename TangentVector>
362 JointDataDerived &
data,
363 const typename Eigen::MatrixBase<ConfigVector> &
qs,
364 const typename Eigen::MatrixBase<TangentVector> & vs)
const
368 data.joint_v = vs.template segment<NV>(
idx_v());
372 template<
typename VectorLike,
typename Matrix6Like>
374 JointDataDerived &
data,
375 const Eigen::MatrixBase<VectorLike> & armature,
376 const Eigen::MatrixBase<Matrix6Like> & I,
377 const bool update_I)
const
381 data.StU.diagonal() += armature;
384 data.UDinv.noalias() = I *
data.Dinv;
392 return std::string(
"JointModelFreeFlyer");
400 template<
typename NewScalar>
413 #include <boost/type_traits.hpp>
417 template<
typename Scalar,
int Options>
419 :
public integral_constant<bool, true>
423 template<
typename Scalar,
int Options>
425 :
public integral_constant<bool, true>
429 template<
typename Scalar,
int Options>
431 :
public integral_constant<bool, true>
435 template<
typename Scalar,
int Options>
437 :
public integral_constant<bool, true>
442 #endif // ifndef __pinocchio_multibody_joint_free_flyer_hpp__
JointFreeFlyerTpl< _Scalar, _Options > JointDerived
std::string shortname() const
#define PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
JointModelBase< JointModelFreeFlyerTpl > Base
MotionZeroTpl< Scalar, Options > Bias_t
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...
MotionDerived::ActionMatrixType motionAction(const MotionBase< MotionDerived > &v) const
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
void forwardKinematics(Transformation_t &M, const Eigen::MatrixBase< ConfigVectorLike > &q_joint) const
SE3Tpl< S1, O1 >::ActionMatrixType ReturnType
PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like) operator*(const Eigen
Matrix6::IdentityReturnType MatrixReturnType
Eigen::Matrix< Scalar, 6, NV, Options > UD_t
Matrix6::IdentityReturnType StDiagonalMatrixSOperationReturnType
Eigen::Matrix< Scalar, NV, NV, Options > D_t
Eigen::Matrix< Scalar, 6, 1, Options > JointForce
void setIndexes(JointIndex id, int q, int v)
MatrixReturnType matrix_impl() const
JointModelFreeFlyerTpl< Scalar, Options > JointModelDerived
Return type of the ation of a Motion onto an object of type D.
SE3Tpl< Scalar, Options > Transformation_t
TridiagonalSymmetricMatrixApplyOnTheLeftReturnType< LhsMatrixType, TridiagonalSymmetricMatrixTpl< S, O > > operator*(const Eigen::MatrixBase< LhsMatrixType > &lhs, const TridiagonalSymmetricMatrixTpl< S, O > &rhs)
EIGEN_DONT_INLINE void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs) const
Eigen::Matrix< Scalar, 6, 6, Options > DenseBase
#define PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR
static std::string classname()
Eigen::Quaternion< Scalar, Options > Quaternion
Eigen::Matrix< Scalar, 6, NV, Options > U_t
JointModelFreeFlyerTpl< NewScalar, Options > cast() const
JointFreeFlyerTpl< _Scalar, _Options > JointDerived
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION(JointModelFreeFlyerTpl)
Free-flyer joint in .
EIGEN_DONT_INLINE void calc(JointDataDerived &data, const Blank, const typename Eigen::MatrixBase< TangentVector > &vs) const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointFreeFlyerTpl< _Scalar, _Options > JointDerived
MotionTpl< Scalar, Options > Motion_t
TransposeConst transpose() const
PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(JointDerived)
Eigen::Matrix< Scalar, NQ, 1, Options > ConfigVector_t
const std::vector< bool > hasConfigurationLimitInTangent() const
PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR ConfigVector_t joint_q
JointDataFreeFlyerTpl< Scalar, Options > JointDataDerived
void calc_aba(JointDataDerived &data, const Eigen::MatrixBase< VectorLike > &armature, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const
MotionTpl<::CppAD::AD< double >, 0 > Motion
Eigen::Matrix< Scalar, 6, 6, Options > ReducedSquaredMatrix
Eigen::Matrix< Scalar, NV, 1, Options > TangentVector_t
JointMotion __mult__(const Eigen::MatrixBase< Vector6Like > &vj) const
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
EIGEN_DONT_INLINE void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs, const typename Eigen::MatrixBase< TangentVector > &vs) const
SE3Tpl< S1, O1 >::ActionMatrixType se3ActionInverse(const SE3Tpl< S1, O1 > &m) const
std::string shortname() const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointFreeFlyerTpl< _Scalar, _Options > JointDerived
JointMotionSubspaceIdentityTpl< Scalar, Options > Constraint_t
static std::string classname()
PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(JointDerived)
#define PINOCCHIO_CONSTRAINT_TYPEDEF_TPL(DERIVED)
const std::vector< bool > hasConfigurationLimit() const
PINOCCHIO_EIGEN_REF_CONST_TYPE(MatrixDerived) operator*(const Eigen
bool isEqual(const JointMotionSubspaceIdentityTpl &) const
Common traits structure to fully define base classes for CRTP.
Eigen::Matrix< Scalar, 6, 6, Options > Matrix6
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.
ForceDense< Derived >::ToVectorConstReturnType operator*(const ForceDense< Derived > &phi)
MotionTpl< Scalar, Options > JointMotion
SE3Tpl< S1, O1 >::ActionMatrixType ReturnType
SE3Tpl< S1, O1 >::ActionMatrixType se3Action(const SE3Tpl< S1, O1 > &m) const
Matrix6::IdentityReturnType ConstMatrixReturnType
JointDataDerived createData() const
Main pinocchio namespace.
EIGEN_DONT_INLINE void calc(JointDataDerived &data, const typename Eigen::MatrixBase< Vector3Derived > &trans, const typename Eigen::QuaternionBase< QuaternionDerived > &quat) const
pinocchio
Author(s):
autogenerated on Mon Dec 16 2024 03:41:02