5 #ifndef __pinocchio_force_dense_hpp__ 6 #define __pinocchio_force_dense_hpp__ 11 template<
typename Derived>
17 template<
typename Derived,
typename MotionDerived>
23 template<
typename Derived>
36 using Base::operator=;
38 Derived &
setZero() { linear().setZero(); angular().setZero();
return derived(); }
39 Derived &
setRandom() { linear().setRandom(); angular().setRandom();
return derived(); }
43 {
return linear() == other.
linear() && angular() == other.
angular(); }
47 {
return other.
derived() == derived(); }
61 return derived().setFrom(other.
derived());
67 EIGEN_STATIC_ASSERT_VECTOR_ONLY(V6); assert(v.size() == 6);
68 linear() = v.template segment<3>(LINEAR);
69 angular() = v.template segment<3>(ANGULAR);
73 ForcePlain
operator-()
const {
return derived().__opposite__(); }
83 { f.
derived().addTo(derived());
return derived(); }
88 ForcePlain
__opposite__()
const {
return ForcePlain(-linear(),-angular()); }
92 {
return ForcePlain(linear()+v.
linear(), angular()+v.
angular()); }
96 {
return ForcePlain(linear()-v.
linear(), angular()-v.
angular()); }
100 { linear() += v.
linear(); angular() += v.
angular();
return derived(); }
102 template<
typename M1>
104 { linear() -= v.
linear(); angular() -= v.
angular();
return derived(); }
106 template<
typename OtherScalar>
107 ForcePlain
__mult__(
const OtherScalar & alpha)
const 108 {
return ForcePlain(alpha*linear(),alpha*angular()); }
110 template<
typename OtherScalar>
111 ForcePlain
__div__(
const OtherScalar & alpha)
const 112 {
return derived().__mult__((OtherScalar)(1)/alpha); }
114 template<
typename F1>
116 {
return phi.
linear().dot(linear()) + phi.
angular().dot(angular()); }
118 template<
typename M1,
typename M2>
125 template<
typename M1>
133 template<
typename M2>
135 {
return derived().isApprox_impl(f, prec);}
137 template<
typename D2>
140 return linear().isApprox(f.
linear(), prec) && angular().isApprox(f.
angular(), prec);
145 return linear().isZero(prec) && angular().isZero(prec);
148 template<
typename S2,
int O2,
typename D2>
156 template<
typename S2,
int O2>
160 se3Action_impl(m,res);
164 template<
typename S2,
int O2,
typename D2>
171 template<
typename S2,
int O2>
175 se3ActionInverse_impl(m,res);
182 <<
" f = " << linear().transpose () << std::endl
183 <<
"tau = " << angular().transpose () << std::endl;
187 ForceRefType
ref() {
return derived().ref(); }
192 template<
typename F1>
199 #endif // ifndef __pinocchio_force_dense_hpp__ JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
Return type of the ation of a Motion onto an object of type D.
bool isZero(const Eigen::MatrixBase< MatrixLike > &m, const typename MatrixLike::RealScalar &prec=Eigen::NumTraits< typename MatrixLike::Scalar >::dummy_precision())
bool isApprox(const ForceDense< M2 > &f, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
Derived & operator+=(const ForceBase< F1 > &f)
ForceBase< Derived > Base
ForcePlain __mult__(const OtherScalar &alpha) const
ForcePlain operator-(const ForceDense< F1 > &f) const
ConstAngularType angular() const
Return the angular part of the force vector.
bool isEqual_impl(const ForceDense< D2 > &other) const
ForcePlain __plus__(const ForceDense< M1 > &v) const
bool isApprox_impl(const ForceDense< D2 > &f, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
void motionAction(const MotionDense< M1 > &v, ForceDense< M2 > &fout) const
bool isZero_impl(const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
ConstLinearType linear() const
Return the linear part of the force vector.
Scalar dot(const MotionDense< F1 > &phi) const
ForcePlain se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m) const
ForcePlain motionAction(const MotionDense< M1 > &v) const
ConstLinearType linear() const
#define FORCE_TYPEDEF_TPL(Derived)
void se3Action_impl(const SE3Tpl< S2, O2 > &m, ForceDense< D2 > &f) const
traits< Derived >::ForceRefType ForceRefType
Derived & __pequ__(const ForceDense< M1 > &v)
ForcePlain se3Action_impl(const SE3Tpl< S2, O2 > &m) const
ConstLinearRef translation() const
Derived & operator-=(const ForceDense< M1 > &v)
Base interface for forces representation.
Derived & __mequ__(const ForceDense< M1 > &v)
Derived & operator=(const Eigen::MatrixBase< V6 > &v)
void se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m, ForceDense< D2 > &f) const
Main pinocchio namespace.
Derived & setFrom(const ForceDense< D2 > &other)
ForcePlain operator-() const
SE3GroupAction< Derived >::ReturnType ReturnType
ForcePlain __opposite__() const
Common traits structure to fully define base classes for CRTP.
Derived & operator+=(const ForceDense< F1 > &f)
MotionAlgebraAction< Derived, MotionDerived >::ReturnType ReturnType
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...
void disp_impl(std::ostream &os) const
ForcePlain __minus__(const ForceDense< M1 > &v) const
ConstAngularRef rotation() const
Derived & operator=(const ForceDense< D2 > &other)
ForcePlain operator+(const ForceDense< F1 > &f) const
MultiplicationOp< InertiaTpl< Scalar, Options >, ConstraintDerived >::ReturnType operator*(const InertiaTpl< Scalar, Options > &Y, const ConstraintBase< ConstraintDerived > &constraint)
.
ForcePlain __div__(const OtherScalar &alpha) const
bool isEqual_impl(const ForceBase< D2 > &other) const