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

#include <joint-spherical-ZYX.hpp>

Classes

struct  ConstraintTranspose
 

Public Types

enum  { NV = 3 }
 
typedef Eigen::Matrix< Scalar, 3, 3, OptionsMatrix3
 

Public Member Functions

template<typename Vector3Like >
JointMotion __mult__ (const Eigen::MatrixBase< Vector3Like > &v) const
 
Matrix3angularSubspace ()
 
const Matrix3angularSubspace () const
 
bool isEqual (const JointMotionSubspaceSphericalZYXTpl &other) const
 
 JointMotionSubspaceSphericalZYXTpl ()
 
template<typename Matrix3Like >
 JointMotionSubspaceSphericalZYXTpl (const Eigen::MatrixBase< Matrix3Like > &subspace)
 
DenseBase matrix_impl () const
 
template<typename MotionDerived >
DenseBase motionAction (const MotionDense< MotionDerived > &m) const
 
int nv_impl () const
 
Matrix3operator() ()
 
const Matrix3operator() () const
 
template<typename S1 , int O1>
Eigen::Matrix< Scalar, 6, 3, Optionsse3Action (const SE3Tpl< S1, O1 > &m) const
 
template<typename S1 , int O1>
Eigen::Matrix< Scalar, 6, 3, Optionsse3ActionInverse (const SE3Tpl< S1, O1 > &m) const
 
ConstraintTranspose transpose () const
 

Protected Attributes

Matrix3 m_S
 

Detailed Description

template<typename _Scalar, int _Options>
struct pinocchio::JointMotionSubspaceSphericalZYXTpl< _Scalar, _Options >

Definition at line 21 of file joint-spherical-ZYX.hpp.

Member Typedef Documentation

◆ Matrix3

template<typename _Scalar , int _Options>
typedef Eigen::Matrix<Scalar, 3, 3, Options> pinocchio::JointMotionSubspaceSphericalZYXTpl< _Scalar, _Options >::Matrix3

Definition at line 61 of file joint-spherical-ZYX.hpp.

Member Enumeration Documentation

◆ anonymous enum

template<typename _Scalar , int _Options>
anonymous enum
Enumerator
NV 

Definition at line 57 of file joint-spherical-ZYX.hpp.

Constructor & Destructor Documentation

◆ JointMotionSubspaceSphericalZYXTpl() [1/2]

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

Definition at line 63 of file joint-spherical-ZYX.hpp.

◆ JointMotionSubspaceSphericalZYXTpl() [2/2]

template<typename _Scalar , int _Options>
template<typename Matrix3Like >
pinocchio::JointMotionSubspaceSphericalZYXTpl< _Scalar, _Options >::JointMotionSubspaceSphericalZYXTpl ( const Eigen::MatrixBase< Matrix3Like > &  subspace)
inline

Definition at line 68 of file joint-spherical-ZYX.hpp.

Member Function Documentation

◆ __mult__()

template<typename _Scalar , int _Options>
template<typename Vector3Like >
JointMotion pinocchio::JointMotionSubspaceSphericalZYXTpl< _Scalar, _Options >::__mult__ ( const Eigen::MatrixBase< Vector3Like > &  v) const
inline

Definition at line 75 of file joint-spherical-ZYX.hpp.

◆ angularSubspace() [1/2]

template<typename _Scalar , int _Options>
Matrix3& pinocchio::JointMotionSubspaceSphericalZYXTpl< _Scalar, _Options >::angularSubspace ( )
inline

Definition at line 194 of file joint-spherical-ZYX.hpp.

◆ angularSubspace() [2/2]

template<typename _Scalar , int _Options>
const Matrix3& pinocchio::JointMotionSubspaceSphericalZYXTpl< _Scalar, _Options >::angularSubspace ( ) const
inline

Definition at line 198 of file joint-spherical-ZYX.hpp.

◆ isEqual()

template<typename _Scalar , int _Options>
bool pinocchio::JointMotionSubspaceSphericalZYXTpl< _Scalar, _Options >::isEqual ( const JointMotionSubspaceSphericalZYXTpl< _Scalar, _Options > &  other) const
inline

Definition at line 203 of file joint-spherical-ZYX.hpp.

◆ matrix_impl()

template<typename _Scalar , int _Options>
DenseBase pinocchio::JointMotionSubspaceSphericalZYXTpl< _Scalar, _Options >::matrix_impl ( ) const
inline

Definition at line 131 of file joint-spherical-ZYX.hpp.

◆ motionAction()

template<typename _Scalar , int _Options>
template<typename MotionDerived >
DenseBase pinocchio::JointMotionSubspaceSphericalZYXTpl< _Scalar, _Options >::motionAction ( const MotionDense< MotionDerived > &  m) const
inline

Definition at line 182 of file joint-spherical-ZYX.hpp.

◆ nv_impl()

template<typename _Scalar , int _Options>
int pinocchio::JointMotionSubspaceSphericalZYXTpl< _Scalar, _Options >::nv_impl ( ) const
inline

Definition at line 90 of file joint-spherical-ZYX.hpp.

◆ operator()() [1/2]

template<typename _Scalar , int _Options>
Matrix3& pinocchio::JointMotionSubspaceSphericalZYXTpl< _Scalar, _Options >::operator() ( )
inline

Definition at line 81 of file joint-spherical-ZYX.hpp.

◆ operator()() [2/2]

template<typename _Scalar , int _Options>
const Matrix3& pinocchio::JointMotionSubspaceSphericalZYXTpl< _Scalar, _Options >::operator() ( ) const
inline

Definition at line 85 of file joint-spherical-ZYX.hpp.

◆ se3Action()

template<typename _Scalar , int _Options>
template<typename S1 , int O1>
Eigen::Matrix<Scalar, 6, 3, Options> pinocchio::JointMotionSubspaceSphericalZYXTpl< _Scalar, _Options >::se3Action ( const SE3Tpl< S1, O1 > &  m) const
inline

Definition at line 144 of file joint-spherical-ZYX.hpp.

◆ se3ActionInverse()

template<typename _Scalar , int _Options>
template<typename S1 , int O1>
Eigen::Matrix<Scalar, 6, 3, Options> pinocchio::JointMotionSubspaceSphericalZYXTpl< _Scalar, _Options >::se3ActionInverse ( const SE3Tpl< S1, O1 > &  m) const
inline

Definition at line 166 of file joint-spherical-ZYX.hpp.

◆ transpose()

template<typename _Scalar , int _Options>
ConstraintTranspose pinocchio::JointMotionSubspaceSphericalZYXTpl< _Scalar, _Options >::transpose ( ) const
inline

Definition at line 126 of file joint-spherical-ZYX.hpp.

Member Data Documentation

◆ m_S

template<typename _Scalar , int _Options>
Matrix3 pinocchio::JointMotionSubspaceSphericalZYXTpl< _Scalar, _Options >::m_S
protected

Definition at line 209 of file joint-spherical-ZYX.hpp.


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


pinocchio
Author(s):
autogenerated on Sat Jun 22 2024 02:41:52