52 #ifndef ATIFORCETORQUESENSORHWCAN_INCLUDEDEF_H 53 #define ATIFORCETORQUESENSORHWCAN_INCLUDEDEF_H 67 #define READ_MATRIX 0x2 68 #define READ_SERIALNR 0x5 70 #define READ_COUNTSPERU 0x7 71 #define READ_UNITCODE 0x8 72 #define READ_DIAGNOV 0X9 74 #define SET_BASEID 0xD 76 #define READ_FIRMWARE 0xF 78 #define ATI_CAN_BAUD_2M 0 79 #define ATI_CAN_BAUD_1M 1 80 #define ATI_CAN_BAUD_500K 3 81 #define ATI_CAN_BAUD_250K 7 91 bool initCommunication(
int can_type, std::string can_path,
int can_baudrate,
int base_identifier);
100 bool readFTData(
int statusCode,
double& Fx,
double& Fy,
double& Fz,
double& Tx,
double& Ty,
double& Tz);
104 void SetGaugeOffset(
float sg0Off,
float sg1Off,
float sg2Off,
float sg3Off,
float sg4Off,
float sg5Off);
105 void SetGaugeGain(
float gg0,
float gg1,
float gg2,
float gg3,
float gg4,
float gg5);
106 void SetFXGain(
float fxg0,
float fxg1,
float fxg2,
float fxg3,
float fxg4,
float fxg5);
107 void SetFYGain(
float fyg0,
float fyg1,
float fyg2,
float fyg3,
float fyg4,
float fyg5);
108 void SetFZGain(
float fzg0,
float fzg1,
float fzg2,
float fzg3,
float fzg4,
float fzg5);
109 void SetTXGain(
float txg0,
float txg1,
float txg2,
float txg3,
float txg4,
float txg5);
110 void SetTYGain(
float tyg0,
float tyg1,
float tyg2,
float tyg3,
float tyg4,
float tyg5);
111 void SetTZGain(
float tzg0,
float tzg1,
float tzg2,
float tzg3,
float tzg4,
float tzg5);
147 void ReadMatrix(
int axis, Eigen::VectorXf& vec);
void StrainGaugeToForce(int &sg0, int &sg1, int &sg2, int &sg3, int &sg4, int &sg5)
bool SetActiveCalibrationMatrix(int num)
union ATIForceTorqueSensorHWCan::@1 intbBuf
bool SetBaseIdentifier(int identifier)
void SetFYGain(float fyg0, float fyg1, float fyg2, float fyg3, float fyg4, float fyg5)
bool readFTData(int statusCode, double &Fx, double &Fy, double &Fz, double &Tx, double &Ty, double &Tz)
Eigen::VectorXf m_v3FYGain
void SetTXGain(float txg0, float txg1, float txg2, float txg3, float txg4, float txg5)
void SetFXGain(float fxg0, float fxg1, float fxg2, float fxg3, float fxg4, float fxg5)
Eigen::VectorXf m_v3TZGain
bool ReadFTSerialNumber()
void ReadCalibrationMatrix()
union ATIForceTorqueSensorHWCan::@2 fbBuf
Eigen::VectorXf m_v3FXGain
bool SetBaudRate(int value)
bool ReadFirmwareVersion()
void SetGaugeGain(float gg0, float gg1, float gg2, float gg3, float gg4, float gg5)
~ATIForceTorqueSensorHWCan()
bool readDiagnosticADCVoltages(int index, short int &value)
void SetGaugeOffset(float sg0Off, float sg1Off, float sg2Off, float sg3Off, float sg4Off, float sg5Off)
void SetTYGain(float tyg0, float tyg1, float tyg2, float tyg3, float tyg4, float tyg5)
union ATIForceTorqueSensorHWCan::@0 ibBuf
Eigen::VectorXf m_v3GaugeGain
bool initCommunication(int can_type, std::string can_path, int can_baudrate, int base_identifier)
void SetFZGain(float fzg0, float fzg1, float fzg2, float fzg3, float fzg4, float fzg5)
Eigen::MatrixXf m_vForceData
Eigen::VectorXf m_v3StrainGaigeOffset
Eigen::VectorXf m_v3TYGain
Eigen::VectorXf m_v3FZGain
void ReadMatrix(int axis, Eigen::VectorXf &vec)
Eigen::VectorXf m_v3TXGain
ATIForceTorqueSensorHWCan()
Eigen::MatrixXf m_mXCalibMatrix
void SetTZGain(float tzg0, float tzg1, float tzg2, float tzg3, float tzg4, float tzg5)