ForceTorqueCtrl Class Reference

#include <ForceTorqueCtrl.h>

List of all members.

Public Member Functions

void CalcCalibMatrix ()
 ForceTorqueCtrl ()
bool Init ()
void ReadCalibrationMatrix ()
void ReadFirmwareVersion ()
void ReadFTSerialNumber ()
void ReadSGData (double &Fx, double &Fy, double &Fz, double &Tx, double &Ty, double &Tz)
void SetActiveCalibrationMatrix (int num)
void SetCalibMatrix ()
void SetFXGain (float fxg0, float fxg1, float fxg2, float fxg3, float fxg4, float fxg5)
void SetFYGain (float fyg0, float fyg1, float fyg2, float fyg3, float fyg4, float fyg5)
void SetFZGain (float fzg0, float fzg1, float fzg2, float fzg3, float fzg4, float fzg5)
void SetGaugeGain (float gg0, float gg1, float gg2, float gg3, float gg4, float gg5)
void SetGaugeOffset (float sg0Off, float sg1Off, float sg2Off, float sg3Off, float sg4Off, float sg5Off)
void SetTXGain (float txg0, float txg1, float txg2, float txg3, float txg4, float txg5)
void SetTYGain (float tyg0, float tyg1, float tyg2, float tyg3, float tyg4, float tyg5)
void SetTZGain (float tzg0, float tzg1, float tzg2, float tzg3, float tzg4, float tzg5)
void StrainGaugeToForce (int &sg0, int &sg1, int &sg2, int &sg3, int &sg4, int &sg5)
 ~ForceTorqueCtrl ()

Protected Member Functions

void initCan ()

Private Member Functions

void ReadMatrix (int axis, Eigen::VectorXf &vec)

Private Attributes

CanMsg CMsg
unsigned int d_len
union {
   char   bytes [4]
   float   value
fbBuf
union {
   char   bytes [2]
   short int   value
ibBuf
CanItfm_Can
Eigen::MatrixXf m_mXCalibMatrix
Eigen::VectorXf m_v3FXGain
Eigen::VectorXf m_v3FYGain
Eigen::VectorXf m_v3FZGain
Eigen::VectorXf m_v3GaugeGain
Eigen::VectorXf m_v3StrainGaigeOffset
Eigen::VectorXf m_v3TXGain
Eigen::VectorXf m_v3TYGain
Eigen::VectorXf m_v3TZGain
Eigen::MatrixXf m_vForceData
std::ofstream out

Detailed Description

Definition at line 22 of file ForceTorqueCtrl.h.


Constructor & Destructor Documentation

ForceTorqueCtrl::ForceTorqueCtrl (  ) 

Definition at line 4 of file ForceTorqueCtrl.cpp.

ForceTorqueCtrl::~ForceTorqueCtrl (  ) 

Definition at line 9 of file ForceTorqueCtrl.cpp.


Member Function Documentation

void ForceTorqueCtrl::CalcCalibMatrix (  ) 

Definition at line 402 of file ForceTorqueCtrl.cpp.

bool ForceTorqueCtrl::Init (  ) 

Definition at line 13 of file ForceTorqueCtrl.cpp.

void ForceTorqueCtrl::initCan (  )  [protected]

Definition at line 20 of file ForceTorqueCtrl.cpp.

void ForceTorqueCtrl::ReadCalibrationMatrix (  ) 

Definition at line 82 of file ForceTorqueCtrl.cpp.

void ForceTorqueCtrl::ReadFirmwareVersion (  ) 

Definition at line 211 of file ForceTorqueCtrl.cpp.

void ForceTorqueCtrl::ReadFTSerialNumber (  ) 

Definition at line 26 of file ForceTorqueCtrl.cpp.

void ForceTorqueCtrl::ReadMatrix ( int  axis,
Eigen::VectorXf &  vec 
) [private]

Definition at line 112 of file ForceTorqueCtrl.cpp.

void ForceTorqueCtrl::ReadSGData ( double &  Fx,
double &  Fy,
double &  Fz,
double &  Tx,
double &  Ty,
double &  Tz 
)

Definition at line 242 of file ForceTorqueCtrl.cpp.

void ForceTorqueCtrl::SetActiveCalibrationMatrix ( int  num  ) 

Definition at line 51 of file ForceTorqueCtrl.cpp.

void ForceTorqueCtrl::SetCalibMatrix (  ) 

Definition at line 450 of file ForceTorqueCtrl.cpp.

void ForceTorqueCtrl::SetFXGain ( float  fxg0,
float  fxg1,
float  fxg2,
float  fxg3,
float  fxg4,
float  fxg5 
)

Definition at line 357 of file ForceTorqueCtrl.cpp.

void ForceTorqueCtrl::SetFYGain ( float  fyg0,
float  fyg1,
float  fyg2,
float  fyg3,
float  fyg4,
float  fyg5 
)

Definition at line 364 of file ForceTorqueCtrl.cpp.

void ForceTorqueCtrl::SetFZGain ( float  fzg0,
float  fzg1,
float  fzg2,
float  fzg3,
float  fzg4,
float  fzg5 
)

Definition at line 372 of file ForceTorqueCtrl.cpp.

void ForceTorqueCtrl::SetGaugeGain ( float  gg0,
float  gg1,
float  gg2,
float  gg3,
float  gg4,
float  gg5 
)

Definition at line 349 of file ForceTorqueCtrl.cpp.

void ForceTorqueCtrl::SetGaugeOffset ( float  sg0Off,
float  sg1Off,
float  sg2Off,
float  sg3Off,
float  sg4Off,
float  sg5Off 
)

Definition at line 341 of file ForceTorqueCtrl.cpp.

void ForceTorqueCtrl::SetTXGain ( float  txg0,
float  txg1,
float  txg2,
float  txg3,
float  txg4,
float  txg5 
)

Definition at line 380 of file ForceTorqueCtrl.cpp.

void ForceTorqueCtrl::SetTYGain ( float  tyg0,
float  tyg1,
float  tyg2,
float  tyg3,
float  tyg4,
float  tyg5 
)

Definition at line 387 of file ForceTorqueCtrl.cpp.

void ForceTorqueCtrl::SetTZGain ( float  tzg0,
float  tzg1,
float  tzg2,
float  tzg3,
float  tzg4,
float  tzg5 
)

Definition at line 394 of file ForceTorqueCtrl.cpp.

void ForceTorqueCtrl::StrainGaugeToForce ( int &  sg0,
int &  sg1,
int &  sg2,
int &  sg3,
int &  sg4,
int &  sg5 
)

Definition at line 312 of file ForceTorqueCtrl.cpp.


Member Data Documentation

Definition at line 75 of file ForceTorqueCtrl.h.

Definition at line 52 of file ForceTorqueCtrl.h.

unsigned int ForceTorqueCtrl::d_len [private]

Definition at line 54 of file ForceTorqueCtrl.h.

union { ... } ForceTorqueCtrl::fbBuf [private]
union { ... } ForceTorqueCtrl::ibBuf [private]

Definition at line 53 of file ForceTorqueCtrl.h.

Eigen::MatrixXf ForceTorqueCtrl::m_mXCalibMatrix [private]

Definition at line 63 of file ForceTorqueCtrl.h.

Eigen::VectorXf ForceTorqueCtrl::m_v3FXGain [private]

Definition at line 57 of file ForceTorqueCtrl.h.

Eigen::VectorXf ForceTorqueCtrl::m_v3FYGain [private]

Definition at line 58 of file ForceTorqueCtrl.h.

Eigen::VectorXf ForceTorqueCtrl::m_v3FZGain [private]

Definition at line 59 of file ForceTorqueCtrl.h.

Eigen::VectorXf ForceTorqueCtrl::m_v3GaugeGain [private]

Definition at line 56 of file ForceTorqueCtrl.h.

Eigen::VectorXf ForceTorqueCtrl::m_v3StrainGaigeOffset [private]

Definition at line 55 of file ForceTorqueCtrl.h.

Eigen::VectorXf ForceTorqueCtrl::m_v3TXGain [private]

Definition at line 60 of file ForceTorqueCtrl.h.

Eigen::VectorXf ForceTorqueCtrl::m_v3TYGain [private]

Definition at line 61 of file ForceTorqueCtrl.h.

Eigen::VectorXf ForceTorqueCtrl::m_v3TZGain [private]

Definition at line 62 of file ForceTorqueCtrl.h.

Eigen::MatrixXf ForceTorqueCtrl::m_vForceData [private]

Definition at line 64 of file ForceTorqueCtrl.h.

std::ofstream ForceTorqueCtrl::out [private]

Definition at line 85 of file ForceTorqueCtrl.h.

Definition at line 82 of file ForceTorqueCtrl.h.

Definition at line 76 of file ForceTorqueCtrl.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines


cob_forcetorque
Author(s): Alexander Bubeck
autogenerated on Fri Jan 11 09:54:28 2013