Public Types | Public Member Functions | Private Attributes
FingerKinematics< N > Class Template Reference

#include <FingerKinematics.h>

List of all members.

Public Types

typedef Eigen::Matrix< double,
N, N > 
JacobianType
typedef Eigen::Matrix< double,
N, 1 > 
JointVectorType
typedef Eigen::Matrix< double,
N, N+1 > 
ReferenceMatrixTransposeInverseType
typedef Eigen::Matrix< double,
N+1, N > 
ReferenceMatrixTransposeType
typedef Eigen::Matrix< double,
N, N+1 > 
ReferenceMatrixType
typedef Eigen::Matrix< double,
N+1, 1 > 
SliderVectorType

Public Member Functions

void calcJacobian (const JointVectorType &jointPos, const JointVectorType &xy, const bool isLeft, JacobianType &jacobian)
double calculateInternalTension (const SliderVectorType &actualTensions)
double findDesiredInternalTension (const double &fmin, const double &fmax, JointVectorType &jointTorques)
 FingerKinematics ()
void forceToJointTorque (const JacobianType &jacobian, const JointVectorType &force, JointVectorType &jointTorque)
void forward (const SliderVectorType &sliderPositions, JointVectorType &jointPositions)
void inverse (const JointVectorType &jointPositions, SliderVectorType &sliderPositions)
void jointSpaceTorqueFeedback (const JointVectorType &torqueError, const JointVectorType &jointKp, const double &tensionError, const double &tensionKp, SliderVectorType &desiredSliders)
void jointToCartesian (const JointVectorType &jointPositions, const bool isLeft, JointVectorType &xy)
void projectToRangeSpace (const SliderVectorType &sliderPositions_in, SliderVectorType &sliderPositions_out)
void setReferenceMatrix (const ReferenceMatrixType &refMatrix_in)
void tensionToJointTorque (const SliderVectorType &actualTensions, JointVectorType &jointTorques)
virtual ~FingerKinematics ()

Private Attributes

SliderVectorType nullSpaceVector
ReferenceMatrixType referenceMatrix
ReferenceMatrixTransposeType referenceMatrixTranspose
ReferenceMatrixTransposeInverseType referenceMatrixTransposeInverse
std::stringstream str

Detailed Description

template<unsigned int N>
class FingerKinematics< N >

Definition at line 15 of file FingerKinematics.h.


Member Typedef Documentation

template<unsigned int N>
typedef Eigen::Matrix<double, N, N> FingerKinematics< N >::JacobianType

Definition at line 24 of file FingerKinematics.h.

template<unsigned int N>
typedef Eigen::Matrix<double, N, 1> FingerKinematics< N >::JointVectorType

Definition at line 19 of file FingerKinematics.h.

template<unsigned int N>
typedef Eigen::Matrix< double, N, N + 1 > FingerKinematics< N >::ReferenceMatrixTransposeInverseType

Definition at line 23 of file FingerKinematics.h.

template<unsigned int N>
typedef Eigen::Matrix< double, N + 1, N > FingerKinematics< N >::ReferenceMatrixTransposeType

Definition at line 22 of file FingerKinematics.h.

template<unsigned int N>
typedef Eigen::Matrix< double, N, N + 1 > FingerKinematics< N >::ReferenceMatrixType

Definition at line 21 of file FingerKinematics.h.

template<unsigned int N>
typedef Eigen::Matrix< double, N + 1, 1 > FingerKinematics< N >::SliderVectorType

Definition at line 20 of file FingerKinematics.h.


Constructor & Destructor Documentation

template<unsigned int N>
FingerKinematics< N >::FingerKinematics ( )

Definition at line 51 of file FingerKinematics.h.

template<unsigned int N>
virtual FingerKinematics< N >::~FingerKinematics ( ) [inline, virtual]

Definition at line 27 of file FingerKinematics.h.


Member Function Documentation

template<unsigned int N>
void FingerKinematics< N >::calcJacobian ( const JointVectorType jointPos,
const JointVectorType xy,
const bool  isLeft,
JacobianType jacobian 
)

Definition at line 232 of file FingerKinematics.h.

template<unsigned int N>
double FingerKinematics< N >::calculateInternalTension ( const SliderVectorType actualTensions)

Definition at line 127 of file FingerKinematics.h.

template<unsigned int N>
double FingerKinematics< N >::findDesiredInternalTension ( const double &  fmin,
const double &  fmax,
JointVectorType jointTorques 
)

Definition at line 133 of file FingerKinematics.h.

template<unsigned int N>
void FingerKinematics< N >::forceToJointTorque ( const JacobianType jacobian,
const JointVectorType force,
JointVectorType jointTorque 
)

Definition at line 349 of file FingerKinematics.h.

template<unsigned int N>
void FingerKinematics< N >::forward ( const SliderVectorType sliderPositions,
JointVectorType jointPositions 
)

Definition at line 102 of file FingerKinematics.h.

template<unsigned int N>
void FingerKinematics< N >::inverse ( const JointVectorType jointPositions,
SliderVectorType sliderPositions 
)

Definition at line 108 of file FingerKinematics.h.

template<unsigned int N>
void FingerKinematics< N >::jointSpaceTorqueFeedback ( const JointVectorType torqueError,
const JointVectorType jointKp,
const double &  tensionError,
const double &  tensionKp,
SliderVectorType desiredSliders 
)

Definition at line 225 of file FingerKinematics.h.

template<unsigned int N>
void FingerKinematics< N >::jointToCartesian ( const JointVectorType jointPositions,
const bool  isLeft,
JointVectorType xy 
)

Definition at line 301 of file FingerKinematics.h.

template<unsigned int N>
void FingerKinematics< N >::projectToRangeSpace ( const SliderVectorType sliderPositions_in,
SliderVectorType sliderPositions_out 
)

Definition at line 114 of file FingerKinematics.h.

template<unsigned int N>
void FingerKinematics< N >::setReferenceMatrix ( const ReferenceMatrixType refMatrix_in)

Definition at line 56 of file FingerKinematics.h.

template<unsigned int N>
void FingerKinematics< N >::tensionToJointTorque ( const SliderVectorType actualTensions,
JointVectorType jointTorques 
)

Definition at line 121 of file FingerKinematics.h.


Member Data Documentation

template<unsigned int N>
SliderVectorType FingerKinematics< N >::nullSpaceVector [private]

Definition at line 47 of file FingerKinematics.h.

template<unsigned int N>
ReferenceMatrixType FingerKinematics< N >::referenceMatrix [private]

Definition at line 44 of file FingerKinematics.h.

Definition at line 45 of file FingerKinematics.h.

Definition at line 46 of file FingerKinematics.h.

template<unsigned int N>
std::stringstream FingerKinematics< N >::str [private]

Definition at line 17 of file FingerKinematics.h.


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


robodyn_mechanisms
Author(s):
autogenerated on Thu Jun 6 2019 21:22:49