6 #ifndef __pinocchio_motion_base_hpp__ 7 #define __pinocchio_motion_base_hpp__ 12 template<
class Derived>
18 Derived &
derived() {
return *
static_cast<Derived*
>(
this); }
19 const Derived &
derived()
const {
return *
static_cast<const Derived*
>(
this); }
26 template<
typename V3Like>
27 void angular(
const Eigen::MatrixBase<V3Like> &
w)
28 {
derived().angular_impl(w.derived()); }
30 template<
typename V3Like>
31 void linear(
const Eigen::MatrixBase<V3Like> &
v)
32 {
derived().linear_impl(v.derived()); }
34 operator PlainReturnType()
const {
return derived().plain(); }
39 operator Vector6()
const {
return toVector(); }
49 {
return derived().isEqual_impl(other.derived()); }
53 {
return !(
derived() == other.derived()); }
61 template<
typename OtherScalar>
64 {
return derived().__mult__(alpha); }
66 template<
typename OtherScalar>
68 {
return derived().__div__(alpha); }
70 template<
typename OtherSpatialType>
72 cross(
const OtherSpatialType &
d)
const 77 bool isApprox(
const Derived & other,
const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
const 78 {
return derived().isApprox_impl(other, prec);}
80 bool isZero(
const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
const 81 {
return derived().isZero_impl(prec);}
83 template<
typename S2,
int O2>
86 {
return derived().se3Action_impl(m); }
88 template<
typename S2,
int O2>
91 {
return derived().se3ActionInverse_impl(m); }
93 template<
typename ForceDerived>
96 void disp(std::ostream & os)
const {
derived().disp_impl(os); }
97 friend std::ostream & operator << (std::ostream & os, const MotionBase<Derived> &
v)
105 template<
typename MotionDerived>
115 #endif // ifndef __pinocchio_motion_base_hpp__ JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
Derived & operator-=(const MotionBase< Derived > &v)
bool operator==(const MotionBase< M2 > &other) const
PlainReturnType plain() const
MotionTpl< Scalar, Options > motion(const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata)
Visit a JointDataTpl through JointMotionVisitor to get the joint internal motion as a dense motion...
Derived operator-(const MotionBase< Derived > &v) const
void linear(const Eigen::MatrixBase< V3Like > &v)
MotionAlgebraAction< OtherSpatialType, Derived >::ReturnType cross(const OtherSpatialType &d) const
SE3GroupAction< Derived >::ReturnType se3ActionInverse(const SE3Tpl< S2, O2 > &m) const
void angular(const Eigen::MatrixBase< V3Like > &w)
void disp(std::ostream &os) const
bool isApprox(const Derived &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
ConstLinearType linear() const
SE3GroupAction< Derived >::ReturnType se3Action(const SE3Tpl< S2, O2 > &m) const
Derived operator/(const OtherScalar &alpha) const
internal::RHSScalarMultiplication< Derived, OtherScalar >::ReturnType operator*(const OtherScalar &alpha) const
Main pinocchio namespace.
ToVectorReturnType toVector()
MOTION_TYPEDEF_TPL(Derived)
const Derived & derived() const
ToVectorConstReturnType toVector() const
bool operator!=(const MotionBase< M2 > &other) const
Derived operator+(const MotionBase< Derived > &v) const
Derived operator-() const
ActionMatrixType toDualActionMatrix() const
bool isZero(const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
ConstAngularType angular() const
Derived & operator+=(const MotionBase< Derived > &v)
ActionMatrixType toActionMatrix() const
Scalar dot(const ForceDense< ForceDerived > &f) const