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

This class provides the joint command interface for the fingers. More...

#include <JointCommandFinger.h>

Inheritance diagram for JointCommandFinger< N, NHall >:
Inheritance graph
[legend]

List of all members.

Public Member Functions

r2_msgs::JointCapability getCapability ()
r2_msgs::JointCommand getCommandedState ()
sensor_msgs::JointState getCompleteMeasuredState ()
sensor_msgs::JointState getSimpleMeasuredState ()
 JointCommandFinger (const std::string &mechanism, IoFunctions ioFunctions)
void loadCoeffs ()
void setCommand (r2_msgs::JointCommand msg, r2_msgs::JointControlData control)
void setFaultState ()
void updateMeasuredState (r2_msgs::JointControlData msg)
 ~JointCommandFinger ()

Private Attributes

bool activeStiffnessOn
FingerController< N, NHall > controller
FingerController< N, NHall >
::SliderVectorType 
desiredSliders
FingerController< N, NHall >
::SliderVectorType 
desiredSliderVels
std::vector< double > effortVals
FingerController< N, NHall >
::SliderVectorType 
encoderOffset
boost::array< std::string, N+1 > encoderOffsetElements
boost::array< std::string, N+1 > encoderStateElements
FingerController< N, NHall >
::SliderVectorType 
encoderVec
FingerController< N, NHall >
::HallVectorType 
filteredHallVec
FingerController< N, NHall >
::SliderVectorType 
filteredSliderVec
bool filterInitialized
ros::Duration fingerBoostCurrentDuration
FingerController< N, NHall >
::SliderVectorType 
fingerBoostMotCom
double fingerBoostTime
ros::Time fingerBoostTimerStart
boost::array< std::string, NHall > hallStateElements
FingerController< N, NHall >
::HallVectorType 
hallVec
FingerController< N, NHall >
::HallVectorType 
hallVecRaw
bool isLeft
FingerController< N, NHall >
::JointVectorType 
jointVec
FingerController< N, NHall >
::SliderVectorType 
kTendon
double kTendonDefault
boost::array< std::string, N+1 > motComCommandElements
std::string nameActiveStiffnessOn
std::string nameCoeffState
boost::array< std::string, N+1 > nameFingerBoost
std::string nameFingerBoostTime
std::string nameIsCalibrated
boost::array< std::string, N+1 > nameKTendon
std::string nameUseCartesian
double positionAlpha
std::vector< double > positionVals
std::vector< double > prevPositionVals
FingerController< N, NHall >
::JointVectorType 
prevSmoothedPos
FingerController< N, NHall >
::SliderVectorType 
sliderMotComs
boost::array< std::string, N+1 > sliderOffsetElements
boost::array< std::string, N+1 > sliderTarePosElements
FingerController< N, NHall >
::SliderVectorType 
sliderVec
FingerController< N, NHall >
::SliderVectorType 
sliderVel
FingerController< N, NHall >
::JointVectorType 
smoothedPos
boost::ptr_array
< EmbeddedSmoother, N > 
smoother
std::vector< std::string >
::iterator 
strVecIt
boost::array< std::string, N+1 > tensionAStateElements
FingerController< N, NHall >
::SliderVectorType 
tensionAVec
boost::array< std::string, N+1 > tensionBStateElements
FingerController< N, NHall >
::SliderVectorType 
tensionBVec
double tensionMin
boost::array< std::string, N+1 > tensionOffsetElements
FingerController< N, NHall >
::SliderVectorType 
tensionVec
double timestep
bool tubeTared
bool useCartesian
std::vector< double > velocityVals

Detailed Description

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

This class provides the joint command interface for the fingers.

Definition at line 27 of file JointCommandFinger.h.


Constructor & Destructor Documentation

template<unsigned int N, unsigned int NHall>
JointCommandFinger< N, NHall >::JointCommandFinger ( const std::string &  mechanism,
IoFunctions  ioFunctions 
)

Definition at line 103 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall>
JointCommandFinger< N, NHall >::~JointCommandFinger ( )

Definition at line 298 of file JointCommandFinger.h.


Member Function Documentation

template<unsigned int N, unsigned int NHall>
r2_msgs::JointCapability JointCommandFinger< N, NHall >::getCapability ( ) [virtual]

Implements JointCommandInterface.

Definition at line 1113 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall>
r2_msgs::JointCommand JointCommandFinger< N, NHall >::getCommandedState ( ) [virtual]

Implements JointCommandInterface.

Definition at line 909 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall>
sensor_msgs::JointState JointCommandFinger< N, NHall >::getCompleteMeasuredState ( ) [virtual]

Implements JointCommandInterface.

Definition at line 863 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall>
sensor_msgs::JointState JointCommandFinger< N, NHall >::getSimpleMeasuredState ( ) [virtual]

Implements JointCommandInterface.

Definition at line 844 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall>
void JointCommandFinger< N, NHall >::loadCoeffs ( ) [virtual]

Initialize messages

avoiding forward rate kinematics here

Parse parameter file

State & Command Elements

Coeffs

multiloop parameters

Reference Matrix

live coeff

Implements JointCommandInterface.

Definition at line 302 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall>
void JointCommandFinger< N, NHall >::setCommand ( r2_msgs::JointCommand  msg,
r2_msgs::JointControlData  control 
) [virtual]
Todo:
this doesn't seem right: velocity[N]???

we are not in drive, so set motcoms to 0

Implements JointCommandInterface.

Definition at line 921 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall>
void JointCommandFinger< N, NHall >::setFaultState ( )

Definition at line 916 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall>
void JointCommandFinger< N, NHall >::updateMeasuredState ( r2_msgs::JointControlData  msg) [virtual]

Implements JointCommandInterface.

Definition at line 660 of file JointCommandFinger.h.


Member Data Documentation

template<unsigned int N, unsigned int NHall = N>
bool JointCommandFinger< N, NHall >::activeStiffnessOn [private]

Definition at line 60 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
FingerController<N, NHall> JointCommandFinger< N, NHall >::controller [private]

Definition at line 44 of file JointCommandFinger.h.

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

Definition at line 54 of file JointCommandFinger.h.

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

Definition at line 54 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
std::vector<double> JointCommandFinger< N, NHall >::effortVals [private]

Definition at line 70 of file JointCommandFinger.h.

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

Definition at line 54 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
boost::array< std::string, N + 1 > JointCommandFinger< N, NHall >::encoderOffsetElements [private]

Definition at line 89 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
boost::array< std::string, N + 1 > JointCommandFinger< N, NHall >::encoderStateElements [private]

Definition at line 46 of file JointCommandFinger.h.

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

Definition at line 54 of file JointCommandFinger.h.

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

Definition at line 80 of file JointCommandFinger.h.

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

Definition at line 79 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
bool JointCommandFinger< N, NHall >::filterInitialized [private]

Definition at line 84 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
ros::Duration JointCommandFinger< N, NHall >::fingerBoostCurrentDuration [private]

Definition at line 65 of file JointCommandFinger.h.

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

Definition at line 55 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
double JointCommandFinger< N, NHall >::fingerBoostTime [private]

Definition at line 64 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
ros::Time JointCommandFinger< N, NHall >::fingerBoostTimerStart [private]

Definition at line 66 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
boost::array<std::string, NHall> JointCommandFinger< N, NHall >::hallStateElements [private]

Definition at line 45 of file JointCommandFinger.h.

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

Definition at line 53 of file JointCommandFinger.h.

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

Definition at line 53 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
bool JointCommandFinger< N, NHall >::isLeft [private]

Definition at line 62 of file JointCommandFinger.h.

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

Definition at line 52 of file JointCommandFinger.h.

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

Definition at line 55 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
double JointCommandFinger< N, NHall >::kTendonDefault [private]

Definition at line 59 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
boost::array< std::string, N + 1 > JointCommandFinger< N, NHall >::motComCommandElements [private]

Definition at line 49 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
std::string JointCommandFinger< N, NHall >::nameActiveStiffnessOn [private]

Definition at line 95 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
std::string JointCommandFinger< N, NHall >::nameCoeffState [private]

Definition at line 88 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
boost::array< std::string, N + 1 > JointCommandFinger< N, NHall >::nameFingerBoost [private]

Definition at line 99 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
std::string JointCommandFinger< N, NHall >::nameFingerBoostTime [private]

Definition at line 97 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
std::string JointCommandFinger< N, NHall >::nameIsCalibrated [private]

Definition at line 87 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
boost::array< std::string, N + 1 > JointCommandFinger< N, NHall >::nameKTendon [private]

Definition at line 98 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
std::string JointCommandFinger< N, NHall >::nameUseCartesian [private]

Definition at line 96 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
double JointCommandFinger< N, NHall >::positionAlpha [private]

Definition at line 83 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
std::vector<double> JointCommandFinger< N, NHall >::positionVals [private]

Definition at line 68 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
std::vector<double> JointCommandFinger< N, NHall >::prevPositionVals [private]

Definition at line 81 of file JointCommandFinger.h.

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

Definition at line 76 of file JointCommandFinger.h.

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

Definition at line 56 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
boost::array< std::string, N + 1 > JointCommandFinger< N, NHall >::sliderOffsetElements [private]

Definition at line 90 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
boost::array< std::string, N + 1 > JointCommandFinger< N, NHall >::sliderTarePosElements [private]

Definition at line 91 of file JointCommandFinger.h.

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

Definition at line 54 of file JointCommandFinger.h.

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

Definition at line 56 of file JointCommandFinger.h.

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

Definition at line 75 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
boost::ptr_array<EmbeddedSmoother, N> JointCommandFinger< N, NHall >::smoother [private]

Definition at line 74 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
std::vector<std::string>::iterator JointCommandFinger< N, NHall >::strVecIt [private]

Definition at line 73 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
boost::array< std::string, N + 1 > JointCommandFinger< N, NHall >::tensionAStateElements [private]

Definition at line 47 of file JointCommandFinger.h.

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

Definition at line 55 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
boost::array< std::string, N + 1 > JointCommandFinger< N, NHall >::tensionBStateElements [private]

Definition at line 48 of file JointCommandFinger.h.

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

Definition at line 55 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
double JointCommandFinger< N, NHall >::tensionMin [private]

Definition at line 63 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
boost::array< std::string, N + 1 > JointCommandFinger< N, NHall >::tensionOffsetElements [private]

Definition at line 92 of file JointCommandFinger.h.

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

Definition at line 55 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
double JointCommandFinger< N, NHall >::timestep [private]

Definition at line 82 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
bool JointCommandFinger< N, NHall >::tubeTared [private]

Definition at line 58 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
bool JointCommandFinger< N, NHall >::useCartesian [private]

Definition at line 61 of file JointCommandFinger.h.

template<unsigned int N, unsigned int NHall = N>
std::vector<double> JointCommandFinger< N, NHall >::velocityVals [private]

Definition at line 69 of file JointCommandFinger.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