Public Types | Public Member Functions | Private Attributes
FingerController< N, NHall > Class Template Reference

#include <FingerController.h>

List of all members.

Public Types

typedef Eigen::Matrix< double,
NHall, 1 > 
HallVectorType
typedef FingerKinematics< N >
::JacobianType 
JacobianType
typedef FingerKinematics< N >
::JointVectorType 
JointVectorType
typedef boost::array
< MultiLoopController, N+1 > 
MultiLoopVectorType
typedef FingerKinematics< N >
::ReferenceMatrixType 
ReferenceMatrixType
typedef FingerKinematics< N >
::SliderVectorType 
SliderVectorType

Public Member Functions

 FingerController ()
void getCalibratedTensions (const SliderVectorType &tensionA, const SliderVectorType &tensionB, double timestep, SliderVectorType &tensionsCalibrated)
void getDesiredSliders (const JointVectorType &desiredJoints, const SliderVectorType &actualSliders, SliderVectorType &desiredSliders)
 get limited desiredSliders
void getDesiredSlidersStiffness (const JointVectorType &desiredPos, const JointVectorType &actualJoints, const SliderVectorType &actualSliders, const SliderVectorType &actualTensions, const SliderVectorType &sliderVelocities, const bool useCartesian, const bool isLeft, SliderVectorType &desiredSliders)
 get desiredSliders for joint stiffness control
void getHallAngles (const HallVectorType &halls_in, HallVectorType &jointAngles)
void getJointsFromSliders (const SliderVectorType &sliderPositions, JointVectorType &jointAngles)
void getMotComs (const SliderVectorType &desiredSliders, const SliderVectorType &kTendon, const SliderVectorType &actualSliders, const SliderVectorType &actualTensions, const SliderVectorType &sliderVelocities, SliderVectorType &sliderMotComs, SliderVectorType &desiredSliderVels, const SliderVectorType &fingerBoostMotCom)
 update calculate motcoms to achieve desiredSliders
void getSlidersFromEncoders (const SliderVectorType &encoderPositions, SliderVectorType &sliderPositions)
void getSlidersFromJoints (const JointVectorType &jointAngles, SliderVectorType &sliderPositions)
void getXYPos (const JointVectorType &jointAngles, const bool isLeft, JointVectorType &xy, JointVectorType &desiredTorques)
void reset ()
 reset integrators
void setBusVoltage (double busVoltage_in)
void setHallAngleParameters (double scale, const HallVectorType &coeffs0, const HallVectorType &coeffs1, const HallVectorType &coeffs2, const HallVectorType &coeffs3)
void setMillimetersPerCount (double mmPerCount_in)
void setMultiLoopController (const MultiLoopController &mlc_in, unsigned int controllerIndex)
void setReferenceMatrix (const ReferenceMatrixType &refMatrix_in)
void setStiffnessGains (const JointVectorType &K_in, const double kd_in, const double fmin_in, const double fmax_in, const JointVectorType &jointKp_in, const double tensionKp_in, const double tFreq, const double deadband_in)
void setTensionParameters (const SliderVectorType &aGains, const SliderVectorType &bGains, const SliderVectorType &offsets, const SliderVectorType &calibratedStrain_in)
void setTubeTareParameters (const SliderVectorType &sliderOffsets_in, const SliderVectorType &sliderTarePos_in, const SliderVectorType &tensionOffsets_in)
 setTubeTareParameters
virtual ~FingerController ()

Private Attributes

double busVoltage
SliderVectorType calibratedStrain
double deadbandSize
JointVectorType desTorques
double fmax
double fmin
HallVectorType hallCoeffs0
HallVectorType hallCoeffs1
HallVectorType hallCoeffs2
HallVectorType hallCoeffs3
double hallScale
JointVectorType jointKp
JointVectorType K
double kd
FingerKinematics< N > kinematics
double mmPerCount
MultiLoopVectorType multiLoopControllers
SliderVectorType sliderOffsets
SliderVectorType sliderTarePos
SliderVectorType smoothingFactors
double smoothingHz
SliderVectorType tensionAGains
SliderVectorType tensionBGains
double tensionFilterCutoffFreq
double tensionKp
SliderVectorType tensionOffsets
SliderVectorType tensionSensorCalOffsets
SliderVectorType tensionsPrev

Detailed Description

template<unsigned int N, unsigned int NHall = N>
class FingerController< N, NHall >

Definition at line 18 of file FingerController.h.


Member Typedef Documentation

template<unsigned int N, unsigned int NHall = N>
typedef Eigen::Matrix<double, NHall, 1> FingerController< N, NHall >::HallVectorType

Definition at line 25 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
typedef FingerKinematics<N>::JacobianType FingerController< N, NHall >::JacobianType

Definition at line 24 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
typedef FingerKinematics<N>::JointVectorType FingerController< N, NHall >::JointVectorType

Definition at line 22 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
typedef boost::array< MultiLoopController, N + 1 > FingerController< N, NHall >::MultiLoopVectorType

Definition at line 27 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
typedef FingerKinematics<N>::ReferenceMatrixType FingerController< N, NHall >::ReferenceMatrixType

Definition at line 21 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
typedef FingerKinematics<N>::SliderVectorType FingerController< N, NHall >::SliderVectorType

Definition at line 23 of file FingerController.h.


Constructor & Destructor Documentation

template<unsigned int N, unsigned int NHall>
FingerController< N, NHall >::FingerController ( )

Definition at line 122 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
virtual FingerController< N, NHall >::~FingerController ( ) [inline, virtual]

Definition at line 30 of file FingerController.h.


Member Function Documentation

template<unsigned int N, unsigned int NHall>
void FingerController< N, NHall >::getCalibratedTensions ( const SliderVectorType tensionA,
const SliderVectorType tensionB,
double  timestep,
SliderVectorType tensionsCalibrated 
)

Definition at line 421 of file FingerController.h.

template<unsigned int N, unsigned int NHall>
void FingerController< N, NHall >::getDesiredSliders ( const JointVectorType desiredJoints,
const SliderVectorType actualSliders,
SliderVectorType desiredSliders 
)

get limited desiredSliders

"2.54" value adopted from ControlShell. Hardcoded until someone rethinks this math.

Definition at line 238 of file FingerController.h.

template<unsigned int N, unsigned int NHall>
void FingerController< N, NHall >::getDesiredSlidersStiffness ( const JointVectorType desiredPos,
const JointVectorType actualJoints,
const SliderVectorType actualSliders,
const SliderVectorType actualTensions,
const SliderVectorType sliderVelocities,
const bool  useCartesian,
const bool  isLeft,
SliderVectorType desiredSliders 
)

get desiredSliders for joint stiffness control

Definition at line 262 of file FingerController.h.

template<unsigned int N, unsigned int NHall>
void FingerController< N, NHall >::getHallAngles ( const HallVectorType halls_in,
HallVectorType jointAngles 
)

Definition at line 400 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
void FingerController< N, NHall >::getJointsFromSliders ( const SliderVectorType sliderPositions,
JointVectorType jointAngles 
) [inline]

Definition at line 85 of file FingerController.h.

template<unsigned int N, unsigned int NHall>
void FingerController< N, NHall >::getMotComs ( const SliderVectorType desiredSliders,
const SliderVectorType kTendon,
const SliderVectorType actualSliders,
const SliderVectorType actualTensions,
const SliderVectorType sliderVelocities,
SliderVectorType sliderMotComs,
SliderVectorType desiredSliderVels,
const SliderVectorType fingerBoostMotCom 
)

update calculate motcoms to achieve desiredSliders

Definition at line 370 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
void FingerController< N, NHall >::getSlidersFromEncoders ( const SliderVectorType encoderPositions,
SliderVectorType sliderPositions 
) [inline]

Definition at line 80 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
void FingerController< N, NHall >::getSlidersFromJoints ( const JointVectorType jointAngles,
SliderVectorType sliderPositions 
) [inline]

Definition at line 75 of file FingerController.h.

template<unsigned int N, unsigned int NHall>
void FingerController< N, NHall >::getXYPos ( const JointVectorType jointAngles,
const bool  isLeft,
JointVectorType xy,
JointVectorType desiredTorques 
)

Definition at line 445 of file FingerController.h.

template<unsigned int N, unsigned int NHall>
void FingerController< N, NHall >::reset ( )

reset integrators

Definition at line 227 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
void FingerController< N, NHall >::setBusVoltage ( double  busVoltage_in) [inline]

Definition at line 69 of file FingerController.h.

template<unsigned int N, unsigned int NHall>
void FingerController< N, NHall >::setHallAngleParameters ( double  scale,
const HallVectorType coeffs0,
const HallVectorType coeffs1,
const HallVectorType coeffs2,
const HallVectorType coeffs3 
)

Definition at line 152 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
void FingerController< N, NHall >::setMillimetersPerCount ( double  mmPerCount_in) [inline]

Definition at line 55 of file FingerController.h.

template<unsigned int N, unsigned int NHall>
void FingerController< N, NHall >::setMultiLoopController ( const MultiLoopController &  mlc_in,
unsigned int  controllerIndex 
)

Definition at line 199 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
void FingerController< N, NHall >::setReferenceMatrix ( const ReferenceMatrixType refMatrix_in) [inline]

Definition at line 32 of file FingerController.h.

template<unsigned int N, unsigned int NHall>
void FingerController< N, NHall >::setStiffnessGains ( const JointVectorType K_in,
const double  kd_in,
const double  fmin_in,
const double  fmax_in,
const JointVectorType jointKp_in,
const double  tensionKp_in,
const double  tFreq,
const double  deadband_in 
)

Definition at line 214 of file FingerController.h.

template<unsigned int N, unsigned int NHall>
void FingerController< N, NHall >::setTensionParameters ( const SliderVectorType aGains,
const SliderVectorType bGains,
const SliderVectorType offsets,
const SliderVectorType calibratedStrain_in 
)

Definition at line 162 of file FingerController.h.

template<unsigned int N, unsigned int NHall>
void FingerController< N, NHall >::setTubeTareParameters ( const SliderVectorType sliderOffsets_in,
const SliderVectorType sliderTarePos_in,
const SliderVectorType tensionOffsets_in 
)

setTubeTareParameters

Parameters:
encoderOffsets_inencoder value at encoder zero (end of travel)
sliderOffsets_inencoder value at slider tare position (end of tube tare)
sliderTarePos_inslider tare position (mm at end of tube tare)
tensionOffsets_inat tension zero (end of travel)

round sliderTarePos to nearest mmPerCount

Definition at line 171 of file FingerController.h.


Member Data Documentation

template<unsigned int N, unsigned int NHall = N>
double FingerController< N, NHall >::busVoltage [private]

Definition at line 108 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
SliderVectorType FingerController< N, NHall >::calibratedStrain [private]

Definition at line 101 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
double FingerController< N, NHall >::deadbandSize [private]

Definition at line 117 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
JointVectorType FingerController< N, NHall >::desTorques [private]

Definition at line 118 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
double FingerController< N, NHall >::fmax [private]

Definition at line 112 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
double FingerController< N, NHall >::fmin [private]

Definition at line 111 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
HallVectorType FingerController< N, NHall >::hallCoeffs0 [private]

Definition at line 94 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
HallVectorType FingerController< N, NHall >::hallCoeffs1 [private]

Definition at line 95 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
HallVectorType FingerController< N, NHall >::hallCoeffs2 [private]

Definition at line 96 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
HallVectorType FingerController< N, NHall >::hallCoeffs3 [private]

Definition at line 97 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
double FingerController< N, NHall >::hallScale [private]

Definition at line 93 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
JointVectorType FingerController< N, NHall >::jointKp [private]

Definition at line 113 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
JointVectorType FingerController< N, NHall >::K [private]

Definition at line 109 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
double FingerController< N, NHall >::kd [private]

Definition at line 110 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
FingerKinematics<N> FingerController< N, NHall >::kinematics [private]

Definition at line 91 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
double FingerController< N, NHall >::mmPerCount [private]

Definition at line 92 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
MultiLoopVectorType FingerController< N, NHall >::multiLoopControllers [private]

Definition at line 105 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
SliderVectorType FingerController< N, NHall >::sliderOffsets [private]

Definition at line 102 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
SliderVectorType FingerController< N, NHall >::sliderTarePos [private]

Definition at line 103 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
SliderVectorType FingerController< N, NHall >::smoothingFactors [private]

Definition at line 107 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
double FingerController< N, NHall >::smoothingHz [private]

Definition at line 106 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
SliderVectorType FingerController< N, NHall >::tensionAGains [private]

Definition at line 98 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
SliderVectorType FingerController< N, NHall >::tensionBGains [private]

Definition at line 99 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
double FingerController< N, NHall >::tensionFilterCutoffFreq [private]

Definition at line 116 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
double FingerController< N, NHall >::tensionKp [private]

Definition at line 114 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
SliderVectorType FingerController< N, NHall >::tensionOffsets [private]

Definition at line 104 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
SliderVectorType FingerController< N, NHall >::tensionSensorCalOffsets [private]

Definition at line 100 of file FingerController.h.

template<unsigned int N, unsigned int NHall = N>
SliderVectorType FingerController< N, NHall >::tensionsPrev [private]

Definition at line 115 of file FingerController.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