5 #ifndef __pinocchio_motion_dense_hpp__ 6 #define __pinocchio_motion_dense_hpp__ 8 #include "pinocchio/spatial/skew.hpp" 13 template<
typename Derived>
19 template<
typename Derived,
typename MotionDerived>
25 template<
typename Derived>
39 Derived &
setZero() { linear().setZero(); angular().setZero();
return derived(); }
40 Derived &
setRandom() { linear().setRandom(); angular().setRandom();
return derived(); }
45 X.template block <3,3> (ANGULAR, ANGULAR) = X.template block <3,3> (LINEAR, LINEAR) =
skew(angular());
46 X.template block <3,3> (LINEAR, ANGULAR) =
skew(linear());
47 X.template block <3,3> (ANGULAR, LINEAR).setZero();
55 X.template block <3,3> (ANGULAR, ANGULAR) = X.template block <3,3> (LINEAR, LINEAR) =
skew(angular());
56 X.template block <3,3> (ANGULAR, LINEAR) =
skew(linear());
57 X.template block <3,3> (LINEAR, ANGULAR).setZero();
64 {
return linear() == other.
linear() && angular() == other.
angular(); }
68 {
return other.
derived() == derived(); }
82 other.
derived().setTo(derived());
89 EIGEN_STATIC_ASSERT_VECTOR_ONLY(V6); assert(v.size() == 6);
90 linear() = v.template segment<3>(LINEAR);
91 angular() = v.template segment<3>(ANGULAR);
95 MotionPlain
operator-()
const {
return derived().__opposite__(); }
101 template<
typename M1>
103 template<
typename M1>
105 { v.
derived().addTo(derived());
return derived(); }
107 template<
typename M1>
110 MotionPlain
__opposite__()
const {
return MotionPlain(-linear(),-angular()); }
112 template<
typename M1>
114 {
return MotionPlain(linear()+v.
linear(), angular()+v.
angular()); }
116 template<
typename M1>
118 {
return MotionPlain(linear()-v.
linear(), angular()-v.
angular()); }
120 template<
typename M1>
122 { linear() += v.
linear(); angular() += v.
angular();
return derived(); }
124 template<
typename M1>
126 { linear() -= v.
linear(); angular() -= v.
angular();
return derived(); }
128 template<
typename OtherScalar>
129 MotionPlain
__mult__(
const OtherScalar & alpha)
const 130 {
return MotionPlain(alpha*linear(),alpha*angular()); }
132 template<
typename OtherScalar>
133 MotionPlain
__div__(
const OtherScalar & alpha)
const 134 {
return derived().__mult__((OtherScalar)(1)/alpha); }
136 template<
typename F1>
138 {
return phi.
linear().dot(linear()) + phi.
angular().dot(angular()); }
143 return d.motionAction(derived());
146 template<
typename M1,
typename M2>
153 template<
typename M1>
161 template<
typename M2>
164 return derived().isApprox_impl(m2, prec);
167 template<
typename D2>
170 return linear().isApprox(m2.
linear(), prec) && angular().isApprox(m2.
angular(), prec);
175 return linear().isZero(prec) && angular().isZero(prec);
178 template<
typename S2,
int O2,
typename D2>
185 template<
typename S2,
int O2>
190 se3Action_impl(m,res);
194 template<
typename S2,
int O2,
typename D2>
201 template<
typename S2,
int O2>
206 se3ActionInverse_impl(m,res);
213 <<
" v = " << linear().transpose () << std::endl
214 <<
" w = " << angular().transpose () << std::endl;
218 MotionRefType
ref() {
return derived().ref(); }
223 template<
typename M1,
typename M2>
228 template<
typename M1,
typename F1>
233 template<
typename M1>
240 #endif // ifndef __pinocchio_motion_dense_hpp__ JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
bool isZero_impl(const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
MotionPlain __mult__(const OtherScalar &alpha) const
Derived & operator-=(const MotionDense< M1 > &v)
void se3Action_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
MotionPlain motionAction(const MotionDense< M1 > &v) const
SE3GroupAction< Derived >::ReturnType se3Action_impl(const SE3Tpl< S2, O2 > &m) const
Return type of the ation of a Motion onto an object of type D.
#define MOTION_TYPEDEF_TPL(Derived)
bool isZero(const Eigen::MatrixBase< MatrixLike > &m, const typename MatrixLike::RealScalar &prec=Eigen::NumTraits< typename MatrixLike::Scalar >::dummy_precision())
bool isApprox_impl(const MotionDense< D2 > &m2, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
SE3GroupAction< Derived >::ReturnType ReturnType
MotionPlain operator-(const MotionDense< M1 > &v) const
ConstAngularType angular() const
Return the angular part of the force vector.
MotionAlgebraAction< Derived, MotionDerived >::ReturnType ReturnType
Derived & operator=(const Eigen::MatrixBase< V6 > &v)
Scalar dot(const ForceBase< F1 > &phi) const
ConstLinearType linear() const
Return the linear part of the force vector.
void disp_impl(std::ostream &os) const
Derived & __mequ__(const MotionDense< M1 > &v)
bool isApprox(const MotionDense< M2 > &m2, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
ConstLinearType linear() const
ActionMatrixType toDualActionMatrix_impl() const
MotionBase< Derived > Base
MotionPlain __div__(const OtherScalar &alpha) const
MotionPlain operator-() const
MotionAlgebraAction< D, Derived >::ReturnType cross_impl(const D &d) const
ActionMatrixType toActionMatrix_impl() const
MotionPlain operator+(const MotionDense< M1 > &v) const
MotionPlain __opposite__() const
ConstLinearRef translation() const
Derived & operator=(const MotionBase< D2 > &other)
Base interface for forces representation.
Derived & operator=(const MotionDense< D2 > &other)
traits< Derived >::MotionRefType MotionRefType
Derived & operator+=(const MotionBase< M1 > &v)
Derived & __pequ__(const MotionDense< M1 > &v)
Main pinocchio namespace.
SE3GroupAction< Derived >::ReturnType se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m) const
Derived & operator+=(const MotionDense< M1 > &v)
void se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
Common traits structure to fully define base classes for CRTP.
MotionPlain __minus__(const MotionDense< M1 > &v) const
void skew(const Eigen::MatrixBase< Vector3 > &v, const Eigen::MatrixBase< Matrix3 > &M)
Computes the skew representation of a given 3d vector, i.e. the antisymmetric matrix representation o...
ConstAngularType angular() const
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...
MotionDerived::MotionPlain operator^(const MotionDense< MotionDerived > &m1, const MotionPlanarTpl< S2, O2 > &m2)
ConstAngularRef rotation() const
MultiplicationOp< InertiaTpl< Scalar, Options >, ConstraintDerived >::ReturnType operator*(const InertiaTpl< Scalar, Options > &Y, const ConstraintBase< ConstraintDerived > &constraint)
.
void motionAction(const MotionDense< M1 > &v, MotionDense< M2 > &mout) const
bool isEqual_impl(const MotionBase< D2 > &other) const
bool isEqual_impl(const MotionDense< D2 > &other) const
MotionPlain __plus__(const MotionDense< M1 > &v) const