6 #ifndef __pinocchio_joint_prismatic_unaligned_hpp__ 7 #define __pinocchio_joint_prismatic_unaligned_hpp__ 9 #include "pinocchio/macros.hpp" 10 #include "pinocchio/multibody/joint/joint-base.hpp" 11 #include "pinocchio/multibody/joint/joint-translation.hpp" 12 #include "pinocchio/multibody/constraint.hpp" 13 #include "pinocchio/spatial/inertia.hpp" 14 #include "pinocchio/math/matrix.hpp" 22 template<
typename Scalar,
int Options>
28 template<
typename Scalar,
int Options,
typename MotionDerived>
34 template<
typename _Scalar,
int _Options>
39 typedef Eigen::Matrix<Scalar,3,1,Options>
Vector3;
40 typedef Eigen::Matrix<Scalar,6,1,Options>
Vector6;
41 typedef Eigen::Matrix<Scalar,4,4,Options>
Matrix4;
42 typedef Eigen::Matrix<Scalar,6,6,Options>
Matrix6;
59 template<
typename _Scalar,
int _Options>
61 :
MotionBase < MotionPrismaticUnalignedTpl<_Scalar,_Options> >
63 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
68 template<
typename Vector3Like,
typename S2>
71 : m_axis(axis), m_v(v)
72 { EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like,3); }
74 inline PlainReturnType
plain()
const 76 return PlainReturnType(m_axis*m_v,
77 PlainReturnType::Vector3::Zero());
80 template<
typename OtherScalar>
86 template<
typename Derived>
89 other.
linear() += m_axis * m_v;
92 template<
typename Derived>
95 other.
linear().noalias() = m_axis*m_v;
99 template<
typename S2,
int O2,
typename D2>
106 template<
typename S2,
int O2>
110 se3Action_impl(m,res);
114 template<
typename S2,
int O2,
typename D2>
124 template<
typename S2,
int O2>
128 se3ActionInverse_impl(m,res);
132 template<
typename M1,
typename M2>
143 template<
typename M1>
153 return m_axis == other.
m_axis && m_v == other.
m_v;
159 const Vector3 &
axis()
const {
return m_axis; }
160 Vector3 &
axis() {
return m_axis; }
168 template<
typename Scalar,
int Options,
typename MotionDerived>
169 inline typename MotionDerived::MotionPlain
172 typedef typename MotionDerived::MotionPlain
ReturnType;
176 template<
typename MotionDerived,
typename S2,
int O2>
177 inline typename MotionDerived::MotionPlain
186 template<
typename _Scalar,
int _Options>
201 typedef Eigen::Matrix<Scalar,3,1,Options>
Vector3;
204 template<
typename Scalar,
int Options>
208 template<
typename Scalar,
int Options,
typename MotionDerived>
212 template<
typename Scalar,
int Options,
typename ForceDerived>
216 typedef Eigen::Matrix<typename PINOCCHIO_EIGEN_DOT_PRODUCT_RETURN_TYPE(Vector3,typename ForceDense<ForceDerived>::ConstAngularType),1,1,
Options>
ReturnType;
219 template<
typename Scalar,
int Options,
typename ForceSet>
224 typename Eigen::MatrixBase<const ForceSet>::template NRowsBlockXpr<3>::Type
228 template<
typename _Scalar,
int _Options>
230 :
ConstraintBase< ConstraintPrismaticUnalignedTpl<_Scalar,_Options> >
232 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
241 template<
typename Vector3Like>
244 { EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like,3); }
246 template<
typename Vector1Like>
247 JointMotion
__mult__(
const Eigen::MatrixBase<Vector1Like> &
v)
const 249 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector1Like,1);
250 return JointMotion(m_axis,v[0]);
253 template<
typename S1,
int O1>
264 template<
typename S1,
int O1>
282 template<
typename ForceDerived>
293 template<
typename ForceSet>
297 EIGEN_STATIC_ASSERT(ForceSet::RowsAtCompileTime==6,THIS_METHOD_IS_ONLY_FOR_MATRICES_OF_A_SPECIFIC_SIZE)
299 return ref.
axis().transpose() * F.template middleRows<3>(LINEAR);
315 S.template segment<3>(LINEAR) = m_axis;
316 S.template segment<3>(ANGULAR).
setZero();
320 template<
typename MotionDerived>
324 res.template segment<3>(LINEAR).noalias() = v.
angular().cross(m_axis);
325 res.template segment<3>(ANGULAR).
setZero();
330 const Vector3 &
axis()
const {
return m_axis; }
331 Vector3 &
axis() {
return m_axis; }
335 return m_axis == other.
m_axis;
344 template<
typename S1,
int O1,
typename S2,
int O2>
353 template<
typename S1,
int O1,
typename S2,
int O2>
360 static inline ReturnType
run(
const Inertia &
Y,
361 const Constraint & cpu)
365 const S1 &
m = Y.
mass();
366 const typename Inertia::Vector3 &
c = Y.
lever();
368 res.template segment<3>(Constraint::LINEAR).noalias() = m*cpu.
axis();
369 res.template segment<3>(Constraint::ANGULAR).noalias() = c.cross(res.template segment<3>(Constraint::LINEAR));
376 template<
typename M6Like,
typename Scalar,
int Options>
390 template<
typename M6Like,
typename Scalar,
int Options>
395 static inline ReturnType
run(
const Eigen::MatrixBase<M6Like> &
Y,
396 const Constraint & cru)
398 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(M6Like,6,6);
399 return Y.derived().template middleCols<3>(Constraint::LINEAR) * cru.
axis();
406 template<
typename _Scalar,
int _Options>
423 typedef Eigen::Matrix<Scalar,6,NV,Options>
U_t;
424 typedef Eigen::Matrix<Scalar,NV,NV,Options>
D_t;
425 typedef Eigen::Matrix<Scalar,6,NV,Options>
UD_t;
433 template<
typename Scalar,
int Options>
437 template<
typename _Scalar,
int _Options>
439 :
public JointDataBase< JointDataPrismaticUnalignedTpl<_Scalar,_Options> >
441 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
457 : M(Transformation_t::Vector3::Zero())
458 , S(Constraint_t::Vector3::Zero())
459 , v(Constraint_t::Vector3::Zero(),(
Scalar)0)
462 , UDinv(UD_t::Zero())
465 template<
typename Vector3Like>
470 , U(), Dinv(), UDinv()
473 static std::string
classname() {
return std::string(
"JointDataPrismaticUnaligned"); }
478 template<
typename Scalar,
int Options>
483 template<
typename _Scalar,
int _Options>
485 :
public JointModelBase< JointModelPrismaticUnalignedTpl<_Scalar,_Options> >
487 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
497 typedef Eigen::Matrix<Scalar,3,1,_Options>
Vector3;
506 assert(
isUnitary(
axis) &&
"Translation axis is not unitary");
509 template<
typename Vector3Like>
513 EIGEN_STATIC_ASSERT_VECTOR_ONLY(Vector3Like);
514 assert(
isUnitary(axis) &&
"Translation axis is not unitary");
535 template<
typename ConfigVector>
537 const typename Eigen::MatrixBase<ConfigVector> &
qs)
const 540 const Scalar &
q = qs[
idx_q()];
542 data.M.translation().noalias() =
axis *
q;
545 template<
typename ConfigVector,
typename TangentVector>
547 const typename Eigen::MatrixBase<ConfigVector> &
qs,
548 const typename Eigen::MatrixBase<TangentVector> & vs)
const 550 calc(data,qs.derived());
553 const S2 &
v = vs[
idx_v()];
554 data.v.linearRate() =
v;
557 template<
typename Matrix6Like>
558 void calc_aba(JointDataDerived &
data,
const Eigen::MatrixBase<Matrix6Like> & I,
const bool update_I)
const 560 data.U.noalias() = I.template block<6,3> (0,Inertia::LINEAR) *
axis;
561 data.Dinv[0] =
Scalar(1)/
axis.dot(data.U.template segment <3> (Inertia::LINEAR));
562 data.UDinv.noalias() = data.U * data.Dinv;
568 static std::string
classname() {
return std::string(
"JointModelPrismaticUnaligned"); }
572 template<
typename NewScalar>
576 ReturnType
res(
axis.template cast<NewScalar>());
591 #include <boost/type_traits.hpp> 595 template<
typename Scalar,
int Options>
597 :
public integral_constant<bool,true> {};
599 template<
typename Scalar,
int Options>
601 :
public integral_constant<bool,true> {};
603 template<
typename Scalar,
int Options>
605 :
public integral_constant<bool,true> {};
607 template<
typename Scalar,
int Options>
609 :
public integral_constant<bool,true> {};
613 #endif // ifndef __pinocchio_joint_prismatic_unaligned_hpp__ JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
void addTo(MotionDense< Derived > &other) const
static ReturnType run(const Eigen::MatrixBase< M6Like > &Y, const Constraint &cru)
MotionPrismaticUnalignedTpl __mult__(const OtherScalar &alpha) const
SE3GroupAction< ConstraintPrismaticUnalignedTpl >::ReturnType se3Action(const SE3Tpl< S1, O1 > &m) const
Forward declaration of the multiplication operation return type. Should be overloaded, otherwise it will procude a compilation error.
JointModelPrismaticUnalignedTpl< Scalar, Options > JointModelDerived
Constraint::Vector3 Vector3
PlainReturnType plain() const
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
std::string shortname() const
const Vector3 ConstLinearType
traits< ConstraintPrismaticUnalignedTpl< Scalar, Options > >::Vector3 Vector3
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs, const typename Eigen::MatrixBase< TangentVector > &vs) const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointPrismaticUnalignedTpl< _Scalar, _Options > JointDerived
MotionPrismaticUnalignedTpl()
const Scalar & linearRate() 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...
ConstraintPrismaticUnalignedTpl< Scalar, Options > Constraint_t
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...
JointDataDerived createData() const
Return type of the Constraint::Transpose * ForceSet operation.
Return type of the ation of a Motion onto an object of type D.
TransposeConst transpose() const
#define MOTION_TYPEDEF_TPL(Derived)
PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like) operator*(const Eigen
bool isEqual(const JointModelPrismaticUnalignedTpl &other) const
const std::vector< bool > hasConfigurationLimit() const
SE3GroupAction< ConstraintPrismaticUnalignedTpl >::ReturnType se3ActionInverse(const SE3Tpl< S1, O1 > &m) const
Eigen::Matrix< Scalar, 6, 1, Options > ReturnType
const MatrixMatrixProduct< M6LikeColsNonConst, Vector3 >::type ReturnType
const Vector3 & lever() const
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_JOINT_DATA_BASE_DEFAULT_ACCESSOR
bool isEqual(const ConstraintPrismaticUnalignedTpl &other) const
void motionAction(const MotionDense< M1 > &v, MotionDense< M2 > &mout) const
JointModelBase< JointModelPrismaticUnalignedTpl > Base
const ConstraintPrismaticUnalignedTpl & ref
MotionTpl< Scalar, Options > ReturnType
ConstraintPrismaticUnalignedTpl()
Eigen::Matrix< typename PINOCCHIO_EIGEN_DOT_PRODUCT_RETURN_TYPE(Vector3, typename ForceDense< ForceDerived >::ConstAngularType), 1, 1, Options > ReturnType
const Vector3 ConstAngularType
JointModelPrismaticUnalignedTpl(const Scalar &x, const Scalar &y, const Scalar &z)
InertiaTpl< S1, O1 > Inertia
SizeDepType< 3 >::ColsReturn< M6Like >::ConstType M6LikeCols
ConstLinearType linear() const
MultiplicationOp< Inertia, Constraint >::ReturnType ReturnType
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
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.
void se3Action_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
MotionDerived::MotionPlain operator+(const MotionPlanarTpl< Scalar, Options > &m1, const MotionDense< MotionDerived > &m2)
ConstAngularType angular() const
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs) const
void se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
const DenseBase ConstMatrixReturnType
virtual bool isEqual(const CollisionGeometry &other) const=0
Eigen::Matrix< Scalar, 6, 1, Options > DenseBase
#define PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
MultiplicationOp< Eigen::MatrixBase< M6Like >, Constraint >::ReturnType ReturnType
Eigen::internal::remove_const< M6LikeCols >::type M6LikeColsNonConst
ConstraintPrismaticUnalignedTpl< Scalar, Options > Constraint
static std::string classname()
static std::string classname()
DenseBase matrix_impl() const
MotionTpl< Scalar, Options > ReturnType
JointDataPrismaticUnalignedTpl(const Eigen::MatrixBase< Vector3Like > &axis)
Eigen::Matrix< Scalar, 6, 6, Options > Matrix6
#define PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(Joint)
JointModelPrismaticUnalignedTpl()
std::string shortname() const
void setTo(MotionDense< Derived > &other) const
JointDataPrismaticUnalignedTpl< Scalar, Options > JointDataDerived
PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE typedef Eigen::Matrix< Scalar, NQ, 1, Options > ConfigVector_t
ConstraintPrismaticUnalignedTpl< S2, O2 > Constraint
Eigen::Matrix< Scalar, 6, 1, Options > ReturnType
Eigen::Matrix< Scalar, NV, 1, Options > TangentVector_t
DenseBase motionAction(const MotionDense< MotionDerived > &v) const
JointModelPrismaticUnalignedTpl(const Eigen::MatrixBase< Vector3Like > &axis)
void calc_aba(JointDataDerived &data, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const
DenseBase MatrixReturnType
ConstraintPrismaticUnalignedTpl< Scalar, Options > Constraint
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION(JointModelFreeFlyerTpl)
ConstraintForceSetOp< ConstraintPrismaticUnalignedTpl, ForceSet >::ReturnType operator*(const Eigen::MatrixBase< ForceSet > &F)
Eigen::Matrix< Scalar, 3, 1, _Options > Vector3
MotionPlain se3Action_impl(const SE3Tpl< S2, O2 > &m) const
Eigen::Matrix< S2, 6, 1, O2 > ReturnType
TransformTranslationTpl< Scalar, Options > Transformation_t
Eigen::Matrix< Scalar, 6, 1, Options > Vector6
MotionPrismaticUnalignedTpl< Scalar, Options > JointMotion
ConstLinearType linear() const
Return the linear part of the force vector.
traits< ConstraintPrismaticUnalignedTpl >::Vector3 Vector3
#define PINOCCHIO_EIGEN_REF_TYPE(D)
ConstAngularRef rotation() const
MotionPrismaticUnalignedTpl(const Eigen::MatrixBase< Vector3Like > &axis, const S2 &v)
PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR Transformation_t M
Main pinocchio namespace.
ReturnTypeNotDefined ReturnType
JointMotion __mult__(const Eigen::MatrixBase< Vector1Like > &v) 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...
Eigen::Matrix< Scalar, 6, NV, Options > UD_t
Eigen::Matrix< Scalar, 4, 4, Options > Matrix4
const std::vector< bool > hasConfigurationLimitInTangent() const
Eigen::Matrix< Scalar, NV, NV, Options > D_t
void setZero(std::vector< MatType, Eigen::aligned_allocator< MatType > > &Ms)
static ReturnType run(const Inertia &Y, const Constraint &cpu)
Common traits structure to fully define base classes for CRTP.
JointDataPrismaticUnalignedTpl()
MotionTpl< Scalar, Options > MotionPlain
JointPrismaticUnalignedTpl< Scalar, Options > JointDerived
TransposeConst(const ConstraintPrismaticUnalignedTpl &ref)
#define PINOCCHIO_CONSTRAINT_TYPEDEF_TPL(DERIVED)
Vector3 axis
3d main axis of the joint.
traits< ConstraintPrismaticUnalignedTpl< Scalar, Options > >::Vector3 Vector3
const Vector3 & axis() const
Eigen::ProductReturnType< M1, M2 >::Type type
MatrixMatrixProduct< Eigen::Transpose< const Vector3 >, typename Eigen::MatrixBase< const ForceSet >::template NRowsBlockXpr< 3 >::Type >::type ReturnType
MotionPrismaticUnalignedTpl< Scalar, Options > Motion_t
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
const Vector3 & axis() const
Eigen::Matrix< Scalar, 6, NV, Options > U_t
static void motionAction(const MotionDense< MotionDerived > &v, const Eigen::MatrixBase< Mat > &iF, Eigen::MatrixBase< MatRet > const &jF)
Action of a motion on a set of forces, represented by a 6xN matrix whose each column represent a spat...
MotionPrismaticUnalignedTpl< double > MotionPrismaticUnaligned
MotionPlain se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m) const
bool isEqual_impl(const MotionPrismaticUnalignedTpl &other) const
MotionDerived::MotionPlain operator^(const MotionDense< MotionDerived > &m1, const MotionPlanarTpl< S2, O2 > &m2)
MotionPlain motionAction(const MotionDense< M1 > &v) const
ConstraintPrismaticUnalignedTpl(const Eigen::MatrixBase< Vector3Like > &axis)
Matrix4 HomogeneousMatrixType
Return type of the Constraint::Transpose * Force operation.
MotionZeroTpl< Scalar, Options > Bias_t
MotionPlain PlainReturnType
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointPrismaticUnalignedTpl< _Scalar, _Options > JointDerived
ReturnTypeNotDefined ReturnType
MultiplicationOp< InertiaTpl< Scalar, Options >, ConstraintDerived >::ReturnType operator*(const InertiaTpl< Scalar, Options > &Y, const ConstraintBase< ConstraintDerived > &constraint)
.
Eigen::Matrix< Scalar, 1, 1, Options > JointForce
JointPrismaticUnalignedTpl< Scalar, Options > JointDerived
JointModelPrismaticUnalignedTpl< NewScalar, Options > cast() const
#define PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(Joint)