Go to the documentation of this file.
6 #ifndef __pinocchio_spatial_motion_base_hpp__
7 #define __pinocchio_spatial_motion_base_hpp__
12 template<
class Derived>
13 class MotionBase : NumericalBase<Derived>
20 return *
static_cast<Derived *
>(
this);
24 return *
static_cast<const Derived *
>(
this);
29 return *
const_cast<Derived *
>(&
derived());
34 return derived().angular_impl();
42 return derived().angular_impl();
49 template<
typename V3Like>
50 void angular(
const Eigen::MatrixBase<V3Like> &
w)
55 template<
typename V3Like>
56 void linear(
const Eigen::MatrixBase<V3Like> &
v)
61 operator PlainReturnType()
const
72 return derived().toVector_impl();
76 return derived().toVector_impl();
78 operator Vector6()
const
85 return derived().toActionMatrix_impl();
89 return derived().toDualActionMatrix_impl();
91 operator Matrix6()
const
111 return derived().toHomogeneousMatrix_impl();
119 template<
typename M2>
122 return derived().isEqual_impl(other.derived());
125 template<
typename M2>
128 return !(
derived() == other.derived());
133 return derived().__opposite__();
137 return derived().__plus__(
v.derived());
141 return derived().__minus__(
v.derived());
145 return derived().__pequ__(
v.derived());
149 return derived().__mequ__(
v.derived());
152 template<
typename OtherScalar>
159 template<
typename OtherScalar>
165 template<
typename OtherSpatialType>
173 const Derived & other,
174 const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
const
176 return derived().isApprox_impl(other, prec);
179 bool isZero(
const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
const
181 return derived().isZero_impl(prec);
184 template<
typename S2,
int O2>
190 template<
typename S2,
int O2>
193 return derived().se3ActionInverse_impl(
m);
196 template<
typename ForceDerived>
202 void disp(std::ostream & os)
const
214 template<
typename MotionDerived>
215 typename internal::RHSScalarMultiplication<
225 #endif // ifndef __pinocchio_spatial_motion_base_hpp__
SE3GroupAction< Derived >::ReturnType se3Action(const SE3Tpl< S2, O2 > &m) const
Derived & operator+=(const MotionBase< Derived > &v)
bool operator!=(const MotionBase< M2 > &other) const
Derived & const_cast_derived() const
Derived & operator-=(const MotionBase< Derived > &v)
ActionMatrixType toActionMatrix() const
ConstAngularType angular() const
PlainReturnType plain() const
ConstLinearType linear() const
bool isApprox(const Derived &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
bool isZero(const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
void disp(std::ostream &os) const
TridiagonalSymmetricMatrixApplyOnTheLeftReturnType< LhsMatrixType, TridiagonalSymmetricMatrixTpl< S, O > > operator*(const Eigen::MatrixBase< LhsMatrixType > &lhs, const TridiagonalSymmetricMatrixTpl< S, O > &rhs)
bool operator==(const MotionBase< M2 > &other) 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 OtherScalar &alpha) const
MotionAlgebraAction< OtherSpatialType, Derived >::ReturnType cross(const OtherSpatialType &d) const
Scalar dot(const ForceDense< ForceDerived > &f) const
ToVectorConstReturnType toVector() const
friend std::ostream & operator<<(std::ostream &os, const MotionBase< Derived > &v)
MOTION_TYPEDEF_TPL(Derived)
internal::RHSScalarMultiplication< Derived, OtherScalar >::ReturnType operator*(const OtherScalar &alpha) const
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
SE3GroupAction< Derived >::ReturnType se3ActionInverse(const SE3Tpl< S2, O2 > &m) const
Derived operator-() const
Derived operator-(const MotionBase< Derived > &v) const
Derived operator+(const MotionBase< Derived > &v) const
ToVectorReturnType toVector()
ActionMatrixType toDualActionMatrix() const
HomogeneousMatrixType toHomogeneousMatrix() const
The homogeneous representation of the motion vector .
Main pinocchio namespace.
pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:47