Public Types | Public Member Functions | Protected Attributes | List of all members
pinocchio::MotionRevoluteTpl< _Scalar, _Options, axis > Struct Template Reference

#include <joint-revolute.hpp>

Inheritance diagram for pinocchio::MotionRevoluteTpl< _Scalar, _Options, axis >:
Inheritance graph
[legend]

Public Types

typedef SpatialAxis< axis+ANGULAR > Axis
 
typedef Axis::CartesianAxis3 CartesianAxis3
 

Public Member Functions

template<typename OtherScalar >
MotionRevoluteTpl __mult__ (const OtherScalar &alpha) const
 
template<typename MotionDerived >
void addTo (MotionDense< MotionDerived > &v) const
 
Scalar & angularRate ()
 
const Scalar & angularRate () const
 
bool isEqual_impl (const MotionRevoluteTpl &other) const
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW MOTION_TYPEDEF_TPL (MotionRevoluteTpl)
 
template<typename M1 , typename M2 >
EIGEN_STRONG_INLINE void motionAction (const MotionDense< M1 > &v, MotionDense< M2 > &mout) const
 
template<typename M1 >
MotionPlain motionAction (const MotionDense< M1 > &v) const
 
 MotionRevoluteTpl ()
 
 MotionRevoluteTpl (const Scalar &w)
 
template<typename Vector1Like >
 MotionRevoluteTpl (const Eigen::MatrixBase< Vector1Like > &v)
 
PlainReturnType plain () const
 
template<typename S2 , int O2, typename D2 >
void se3Action_impl (const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
 
template<typename S2 , int O2>
MotionPlain se3Action_impl (const SE3Tpl< S2, O2 > &m) const
 
template<typename S2 , int O2, typename D2 >
void se3ActionInverse_impl (const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
 
template<typename S2 , int O2>
MotionPlain se3ActionInverse_impl (const SE3Tpl< S2, O2 > &m) const
 
template<typename MotionDerived >
void setTo (MotionDense< MotionDerived > &m) const
 
- Public Member Functions inherited from pinocchio::MotionBase< MotionRevoluteTpl< _Scalar, _Options, axis > >
ConstAngularType angular () const
 
AngularType angular ()
 
void angular (const Eigen::MatrixBase< V3Like > &w)
 
MotionAlgebraAction< OtherSpatialType, MotionRevoluteTpl< _Scalar, _Options, axis > >::ReturnType cross (const OtherSpatialType &d) const
 
MotionRevoluteTpl< _Scalar, _Options, axis > & derived ()
 
const MotionRevoluteTpl< _Scalar, _Options, axis > & derived () const
 
void disp (std::ostream &os) const
 
Scalar dot (const ForceDense< ForceDerived > &f) const
 
bool isApprox (const MotionRevoluteTpl< _Scalar, _Options, axis > &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
 
bool isZero (const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
 
ConstLinearType linear () const
 
LinearType linear ()
 
void linear (const Eigen::MatrixBase< V3Like > &v)
 
 MOTION_TYPEDEF_TPL (MotionRevoluteTpl< _Scalar, _Options, axis >)
 
 operator Matrix6 () const
 
 operator PlainReturnType () const
 
 operator Vector6 () const
 
bool operator!= (const MotionBase< M2 > &other) const
 
internal::RHSScalarMultiplication< MotionRevoluteTpl< _Scalar, _Options, axis >, OtherScalar >::ReturnType operator* (const OtherScalar &alpha) const
 
MotionRevoluteTpl< _Scalar, _Options, axisoperator+ (const MotionBase< MotionRevoluteTpl< _Scalar, _Options, axis > > &v) const
 
MotionRevoluteTpl< _Scalar, _Options, axis > & operator+= (const MotionBase< MotionRevoluteTpl< _Scalar, _Options, axis > > &v)
 
MotionRevoluteTpl< _Scalar, _Options, axisoperator- () const
 
MotionRevoluteTpl< _Scalar, _Options, axisoperator- (const MotionBase< MotionRevoluteTpl< _Scalar, _Options, axis > > &v) const
 
MotionRevoluteTpl< _Scalar, _Options, axis > & operator-= (const MotionBase< MotionRevoluteTpl< _Scalar, _Options, axis > > &v)
 
MotionRevoluteTpl< _Scalar, _Options, axisoperator/ (const OtherScalar &alpha) const
 
bool operator== (const MotionBase< M2 > &other) const
 
PlainReturnType plain () const
 
SE3GroupAction< MotionRevoluteTpl< _Scalar, _Options, axis > >::ReturnType se3Action (const SE3Tpl< S2, O2 > &m) const
 
SE3GroupAction< MotionRevoluteTpl< _Scalar, _Options, axis > >::ReturnType se3ActionInverse (const SE3Tpl< S2, O2 > &m) const
 
void setZero ()
 
ActionMatrixType toActionMatrix () const
 
ActionMatrixType toDualActionMatrix () const
 
ToVectorConstReturnType toVector () const
 
ToVectorReturnType toVector ()
 

Protected Attributes

Scalar m_w
 

Detailed Description

template<typename _Scalar, int _Options, int axis>
struct pinocchio::MotionRevoluteTpl< _Scalar, _Options, axis >

Definition at line 19 of file joint-revolute.hpp.

Member Typedef Documentation

template<typename _Scalar, int _Options, int axis>
typedef SpatialAxis<axis+ANGULAR> pinocchio::MotionRevoluteTpl< _Scalar, _Options, axis >::Axis

Definition at line 207 of file joint-revolute.hpp.

template<typename _Scalar, int _Options, int axis>
typedef Axis::CartesianAxis3 pinocchio::MotionRevoluteTpl< _Scalar, _Options, axis >::CartesianAxis3

Definition at line 208 of file joint-revolute.hpp.

Constructor & Destructor Documentation

template<typename _Scalar, int _Options, int axis>
pinocchio::MotionRevoluteTpl< _Scalar, _Options, axis >::MotionRevoluteTpl ( )
inline

Definition at line 210 of file joint-revolute.hpp.

template<typename _Scalar, int _Options, int axis>
pinocchio::MotionRevoluteTpl< _Scalar, _Options, axis >::MotionRevoluteTpl ( const Scalar &  w)
inline

Definition at line 212 of file joint-revolute.hpp.

template<typename _Scalar, int _Options, int axis>
template<typename Vector1Like >
pinocchio::MotionRevoluteTpl< _Scalar, _Options, axis >::MotionRevoluteTpl ( const Eigen::MatrixBase< Vector1Like > &  v)
inline

Definition at line 215 of file joint-revolute.hpp.

Member Function Documentation

template<typename _Scalar, int _Options, int axis>
template<typename OtherScalar >
MotionRevoluteTpl pinocchio::MotionRevoluteTpl< _Scalar, _Options, axis >::__mult__ ( const OtherScalar &  alpha) const
inline

Definition at line 225 of file joint-revolute.hpp.

template<typename _Scalar, int _Options, int axis>
template<typename MotionDerived >
void pinocchio::MotionRevoluteTpl< _Scalar, _Options, axis >::addTo ( MotionDense< MotionDerived > &  v) const
inline

Definition at line 239 of file joint-revolute.hpp.

template<typename _Scalar, int _Options, int axis>
Scalar& pinocchio::MotionRevoluteTpl< _Scalar, _Options, axis >::angularRate ( )
inline

Definition at line 299 of file joint-revolute.hpp.

template<typename _Scalar, int _Options, int axis>
const Scalar& pinocchio::MotionRevoluteTpl< _Scalar, _Options, axis >::angularRate ( ) const
inline

Definition at line 300 of file joint-revolute.hpp.

template<typename _Scalar, int _Options, int axis>
bool pinocchio::MotionRevoluteTpl< _Scalar, _Options, axis >::isEqual_impl ( const MotionRevoluteTpl< _Scalar, _Options, axis > &  other) const
inline

Definition at line 302 of file joint-revolute.hpp.

template<typename _Scalar, int _Options, int axis>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW pinocchio::MotionRevoluteTpl< _Scalar, _Options, axis >::MOTION_TYPEDEF_TPL ( MotionRevoluteTpl< _Scalar, _Options, axis )
template<typename _Scalar, int _Options, int axis>
template<typename M1 , typename M2 >
EIGEN_STRONG_INLINE void pinocchio::MotionRevoluteTpl< _Scalar, _Options, axis >::motionAction ( const MotionDense< M1 > &  v,
MotionDense< M2 > &  mout 
) const
inline

Definition at line 282 of file joint-revolute.hpp.

template<typename _Scalar, int _Options, int axis>
template<typename M1 >
MotionPlain pinocchio::MotionRevoluteTpl< _Scalar, _Options, axis >::motionAction ( const MotionDense< M1 > &  v) const
inline

Definition at line 292 of file joint-revolute.hpp.

template<typename _Scalar, int _Options, int axis>
PlainReturnType pinocchio::MotionRevoluteTpl< _Scalar, _Options, axis >::plain ( ) const
inline

Definition at line 222 of file joint-revolute.hpp.

template<typename _Scalar, int _Options, int axis>
template<typename S2 , int O2, typename D2 >
void pinocchio::MotionRevoluteTpl< _Scalar, _Options, axis >::se3Action_impl ( const SE3Tpl< S2, O2 > &  m,
MotionDense< D2 > &  v 
) const
inline

Definition at line 246 of file joint-revolute.hpp.

template<typename _Scalar, int _Options, int axis>
template<typename S2 , int O2>
MotionPlain pinocchio::MotionRevoluteTpl< _Scalar, _Options, axis >::se3Action_impl ( const SE3Tpl< S2, O2 > &  m) const
inline

Definition at line 253 of file joint-revolute.hpp.

template<typename _Scalar, int _Options, int axis>
template<typename S2 , int O2, typename D2 >
void pinocchio::MotionRevoluteTpl< _Scalar, _Options, axis >::se3ActionInverse_impl ( const SE3Tpl< S2, O2 > &  m,
MotionDense< D2 > &  v 
) const
inline

Definition at line 261 of file joint-revolute.hpp.

template<typename _Scalar, int _Options, int axis>
template<typename S2 , int O2>
MotionPlain pinocchio::MotionRevoluteTpl< _Scalar, _Options, axis >::se3ActionInverse_impl ( const SE3Tpl< S2, O2 > &  m) const
inline

Definition at line 273 of file joint-revolute.hpp.

template<typename _Scalar, int _Options, int axis>
template<typename MotionDerived >
void pinocchio::MotionRevoluteTpl< _Scalar, _Options, axis >::setTo ( MotionDense< MotionDerived > &  m) const
inline

Definition at line 231 of file joint-revolute.hpp.

Member Data Documentation

template<typename _Scalar, int _Options, int axis>
Scalar pinocchio::MotionRevoluteTpl< _Scalar, _Options, axis >::m_w
protected

Definition at line 309 of file joint-revolute.hpp.


The documentation for this struct was generated from the following file:


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:06