ati_force_torque_hw_can.h
Go to the documentation of this file.
1 /****************************************************************
2  *
3  * Copyright 2016 Intelligent Industrial Robotics (IIROB) Group,
4  * Institute for Anthropomatics and Robotics (IAR) -
5  * Intelligent Process Control and Robotics (IPR),
6  * Karlsruhe Institute of Technology
7  *
8  * Author: Florian Aumann
9  * Maintainer: Denis Štogl, email: denis.stogl@kit.edu
10  *
11  * Date of update: 2014-2018
12  *
13  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
14  *
15  * Copyright (c) 2010
16  *
17  * Fraunhofer Institute for Manufacturing Engineering
18  * and Automation (IPA)
19  *
20  * Date of creation: June 2010
21  *
22  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
23  *
24  * Redistribution and use in source and binary forms, with or without
25  * modification, are permitted provided that the following conditions are met:
26  *
27  * * Redistributions of source code must retain the above copyright
28  * notice, this list of conditions and the following disclaimer.
29  * * Redistributions in binary form must reproduce the above copyright
30  * notice, this list of conditions and the following disclaimer in the
31  * documentation and/or other materials provided with the distribution.
32  * * Neither the name of the copyright holder nor the names of its
33  * contributors may be used to endorse or promote products derived from
34  * this software without specific prior written permission.
35  *
36  * This program is free software: you can redistribute it and/or modify
37  * it under the terms of the GNU Lesser General Public License LGPL as
38  * published by the Free Software Foundation, either version 3 of the
39  * License, or (at your option) any later version.
40  *
41  * This program is distributed in the hope that it will be useful,
42  * but WITHOUT ANY WARRANTY; without even the implied warranty of
43  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
44  * GNU Lesser General Public License LGPL for more details.
45  *
46  * You should have received a copy of the GNU Lesser General Public
47  * License LGPL along with this program.
48  * If not, see <http://www.gnu.org/licenses/>.
49  *
50  ****************************************************************/
51 
52 #ifndef ATIFORCETORQUESENSORHWCAN_INCLUDEDEF_H
53 #define ATIFORCETORQUESENSORHWCAN_INCLUDEDEF_H
54 
55 #include <iostream>
56 #include <fstream>
57 #include <Eigen/Core>
58 
60 
61 // Headers provided by other cob-packages
62 #include <cob_generic_can/CanItf.h>
63 
64 // opCodes for the ForceTorque Can Interface
65 // set as Can Message ID
66 #define READ_SG 0x0
67 #define READ_MATRIX 0x2
68 #define READ_SERIALNR 0x5
69 #define SET_CALIB 0x6
70 #define READ_COUNTSPERU 0x7
71 #define READ_UNITCODE 0x8
72 #define READ_DIAGNOV 0X9
73 #define RESET 0xC
74 #define SET_BASEID 0xD
75 #define SET_BAUD 0xE
76 #define READ_FIRMWARE 0xF
77 
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
82 
84 {
85 public:
87  ATIForceTorqueSensorHWCan(int can_type, std::string can_path, int can_baudrate, int base_identifier);
89 
90  bool init();
91  bool initCommunication(int can_type, std::string can_path, int can_baudrate, int base_identifier);
92  bool ReadFTSerialNumber();
93  bool ReadCountsPerUnit();
94  bool ReadUnitCodes();
95  bool readDiagnosticADCVoltages(int index, short int& value);
96  bool SetActiveCalibrationMatrix(int num);
97  bool SetBaudRate(int value);
98  bool SetBaseIdentifier(int identifier);
99  bool Reset();
100  bool readFTData(int statusCode, double& Fx, double& Fy, double& Fz, double& Tx, double& Ty, double& Tz);
101  bool ReadFirmwareVersion();
102  void ReadCalibrationMatrix();
103 
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);
112 
113  void SetCalibMatrix();
114  void CalcCalibMatrix();
115  void StrainGaugeToForce(int& sg0, int& sg1, int& sg2, int& sg3, int& sg4, int& sg5);
116 
117 protected:
118  bool initCan();
119 
120  //--------------------------------- Variables
123 
124 private:
127 
129  std::string m_CanDevice;
132 
133  unsigned int d_len;
134  Eigen::VectorXf m_v3StrainGaigeOffset;
135  Eigen::VectorXf m_v3GaugeGain;
136  Eigen::VectorXf m_v3FXGain;
137  Eigen::VectorXf m_v3FYGain;
138  Eigen::VectorXf m_v3FZGain;
139  Eigen::VectorXf m_v3TXGain;
140  Eigen::VectorXf m_v3TYGain;
141  Eigen::VectorXf m_v3TZGain;
142  Eigen::MatrixXf m_mXCalibMatrix;
143  Eigen::MatrixXf m_vForceData;
144 
145  // the Parameter indicates the Axis row to Read
146  // Fx = 0 | Fy = 1 | Fz = 2 | Tx = 3 | Ty = 4 | Tz = 5
147  void ReadMatrix(int axis, Eigen::VectorXf& vec);
148 
149  union
150  {
151  char bytes[2];
152  short int value;
153  } ibBuf;
154 
155  union
156  {
157  char bytes[4];
158  int value;
159  } intbBuf;
160 
161  union
162  {
163  char bytes[4];
164  float value;
165  } fbBuf;
166 
167  std::ofstream out;
168 };
169 
170 #endif
void StrainGaugeToForce(int &sg0, int &sg1, int &sg2, int &sg3, int &sg4, int &sg5)
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)
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)
union ATIForceTorqueSensorHWCan::@2 fbBuf
void SetGaugeGain(float gg0, float gg1, float gg2, float gg3, float gg4, float gg5)
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
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)
void ReadMatrix(int axis, Eigen::VectorXf &vec)
void SetTZGain(float tzg0, float tzg1, float tzg2, float tzg3, float tzg4, float tzg5)


ati_force_torque
Author(s): Denis Štogl, Alexander Bubeck
autogenerated on Thu Sep 17 2020 03:18:35