HandModeliCub.cpp
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * Copyright (C) 2011-2016, High Performance Humanoid Technologies (H2T), Karlsruhe Institute of Technology (KIT), all rights reserved.
5  *
6  * ArmarX is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License version 2 as
8  * published by the Free Software Foundation.
9  *
10  * ArmarX is distributed in the hope that it will be useful, but
11  * WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13  * GNU General Public License for more details.
14  *
15  * You should have received a copy of the GNU General Public License
16  * along with this program. If not, see <http://www.gnu.org/licenses/>.
17  *
18  * @package
19  * @author
20  * @date
21  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
22  * GNU General Public License
23  */
24 #include "HandModeliCub.h"
25 
26 #include <fstream>
27 #include <iostream>
28 
30 
31 namespace visionx
32 {
33  HandModeliCub::HandModeliCub(std::string sConfigFileName,
34  CStereoCalibration* pStereoCalibration)
35  {
36  m_pStereoCalibration = pStereoCalibration;
37 
38  //****************************************
39  // read hand config file
40  //****************************************
41 
42  std::ifstream sFileStream(sConfigFileName.c_str(), std::ifstream::in);
43  if (!sFileStream.good())
44  {
45  ARMARX_WARNING_S << "CHandModelV2 constructor: file " << sConfigFileName
46  << " could not be opened";
47  return;
48  }
49 
50  std::string sLine;
51  Vec3d vTemp;
52  float fTemp;
53  std::vector<std::vector<float>> aJointOffsets;
54  aJointOffsets.resize(5);
55 
56  // offset to thumb base
57  sLine = GetNextNonCommentLine(sFileStream);
58  sscanf(sLine.c_str(), "%f %f %f", &vTemp.x, &vTemp.y, &vTemp.z);
59  m_aOffsetsToFingers.push_back(vTemp);
60 
61  // distance from thumb base joint to second joint
62  sLine = GetNextNonCommentLine(sFileStream);
63  sscanf(sLine.c_str(), "%f", &fTemp);
64  aJointOffsets.at(0).push_back(fTemp);
65 
66  // distance from second to third thumb joint
67  sLine = GetNextNonCommentLine(sFileStream);
68  sscanf(sLine.c_str(), "%f", &fTemp);
69  aJointOffsets.at(0).push_back(fTemp);
70 
71  // distance from third to fourth thumb joint
72  sLine = GetNextNonCommentLine(sFileStream);
73  sscanf(sLine.c_str(), "%f", &fTemp);
74  aJointOffsets.at(0).push_back(fTemp);
75 
76  // distance from fourth thumb joint to fingertip
77  sLine = GetNextNonCommentLine(sFileStream);
78  sscanf(sLine.c_str(), "%f", &fTemp);
79  aJointOffsets.at(0).push_back(fTemp);
80 
81 
82  // offset from palm to index base
83  sLine = GetNextNonCommentLine(sFileStream);
84  sscanf(sLine.c_str(), "%f %f %f", &vTemp.x, &vTemp.y, &vTemp.z);
85  m_aOffsetsToFingers.push_back(vTemp);
86 
87  // distance from index base joint to second joint
88  sLine = GetNextNonCommentLine(sFileStream);
89  sscanf(sLine.c_str(), "%f", &fTemp);
90  aJointOffsets.at(1).push_back(fTemp);
91 
92  // distance from second to third index joint
93  sLine = GetNextNonCommentLine(sFileStream);
94  sscanf(sLine.c_str(), "%f", &fTemp);
95  aJointOffsets.at(1).push_back(fTemp);
96 
97  // distance from third index joint to fingertip
98  sLine = GetNextNonCommentLine(sFileStream);
99  sscanf(sLine.c_str(), "%f", &fTemp);
100  aJointOffsets.at(1).push_back(fTemp);
101 
102 
103  // offset from palm to middle base
104  sLine = GetNextNonCommentLine(sFileStream);
105  sscanf(sLine.c_str(), "%f %f %f", &vTemp.x, &vTemp.y, &vTemp.z);
106  m_aOffsetsToFingers.push_back(vTemp);
107 
108  // distance from middle base joint to second joint
109  sLine = GetNextNonCommentLine(sFileStream);
110  sscanf(sLine.c_str(), "%f", &fTemp);
111  aJointOffsets.at(2).push_back(fTemp);
112 
113  // distance from second to third middle joint
114  sLine = GetNextNonCommentLine(sFileStream);
115  sscanf(sLine.c_str(), "%f", &fTemp);
116  aJointOffsets.at(2).push_back(fTemp);
117 
118  // distance from third middle joint to fingertip
119  sLine = GetNextNonCommentLine(sFileStream);
120  sscanf(sLine.c_str(), "%f", &fTemp);
121  aJointOffsets.at(2).push_back(fTemp);
122 
123 
124  // offset from palm to ring base
125  sLine = GetNextNonCommentLine(sFileStream);
126  sscanf(sLine.c_str(), "%f %f %f", &vTemp.x, &vTemp.y, &vTemp.z);
127  m_aOffsetsToFingers.push_back(vTemp);
128 
129  // distance from ring base joint to second joint
130  sLine = GetNextNonCommentLine(sFileStream);
131  sscanf(sLine.c_str(), "%f", &fTemp);
132  aJointOffsets.at(3).push_back(fTemp);
133 
134  // distance from second to third ring joint
135  sLine = GetNextNonCommentLine(sFileStream);
136  sscanf(sLine.c_str(), "%f", &fTemp);
137  aJointOffsets.at(3).push_back(fTemp);
138 
139  // distance from third ring joint to fingertip
140  sLine = GetNextNonCommentLine(sFileStream);
141  sscanf(sLine.c_str(), "%f", &fTemp);
142  aJointOffsets.at(3).push_back(fTemp);
143 
144 
145  // offset from palm to pinky base
146  sLine = GetNextNonCommentLine(sFileStream);
147  sscanf(sLine.c_str(), "%f %f %f", &vTemp.x, &vTemp.y, &vTemp.z);
148  m_aOffsetsToFingers.push_back(vTemp);
149 
150  // distance from pinky base joint to second joint
151  sLine = GetNextNonCommentLine(sFileStream);
152  sscanf(sLine.c_str(), "%f", &fTemp);
153  aJointOffsets.at(4).push_back(fTemp);
154 
155  // distance from second to third pinky joint
156  sLine = GetNextNonCommentLine(sFileStream);
157  sscanf(sLine.c_str(), "%f", &fTemp);
158  aJointOffsets.at(4).push_back(fTemp);
159 
160  // distance from third pinky joint to fingertip
161  sLine = GetNextNonCommentLine(sFileStream);
162  sscanf(sLine.c_str(), "%f", &fTemp);
163  aJointOffsets.at(4).push_back(fTemp);
164 
165 
166  // read fingertip points
167 
168  int nNumFingertipPoints;
169  sLine = GetNextNonCommentLine(sFileStream);
170  sscanf(sLine.c_str(), "%d", &nNumFingertipPoints);
171  ARMARX_VERBOSE_S << "Number of fingertip points: " << nNumFingertipPoints;
172 
173  float fFingerTipOffsetZ;
174  sLine = GetNextNonCommentLine(sFileStream);
175  sscanf(sLine.c_str(), "%f", &fFingerTipOffsetZ);
176 
177 
178  std::vector<Vec3d> aFingertipPoints;
179  sLine = GetNextNonCommentLine(sFileStream);
180  for (int i = 0; i < nNumFingertipPoints; i++)
181  {
182  sscanf(sLine.c_str(), "%f %f %f", &vTemp.x, &vTemp.y, &vTemp.z);
183  vTemp.z += fFingerTipOffsetZ;
184  aFingertipPoints.push_back(vTemp);
185  std::getline(sFileStream, sLine);
186  }
187 
188 
189  // tracking ball
190  sLine = GetNextNonCommentLine(sFileStream);
191  sscanf(sLine.c_str(),
192  "%f %f %f",
196  sLine = GetNextNonCommentLine(sFileStream);
197  sscanf(sLine.c_str(), "%f", &m_fTrackingBallRadius);
198 
199 
200  //****************************************
201  // construct fingers
202  //****************************************
203 
204  // thumb
205  std::vector<Vec3d> aFingertipPointsThumb;
206  aFingertipPointsThumb.resize(nNumFingertipPoints);
207  for (int i = 0; i < nNumFingertipPoints; i++)
208  {
209  Math3d::SetVec(aFingertipPointsThumb.at(i),
210  aFingertipPoints.at(i).x,
211  aFingertipPoints.at(i).y,
212  aFingertipPoints.at(i).z);
213  }
214  CFinger* pNewFinger = new CFinger(aJointOffsets.at(0), aFingertipPointsThumb);
215  m_aFingers.push_back(pNewFinger);
216 
217  // other fingers
218  for (int i = 1; i <= 4; i++)
219  {
220  pNewFinger = new CFinger(aJointOffsets.at(i), aFingertipPoints);
221  m_aFingers.push_back(pNewFinger);
222  }
223 
224 
225  //****************************************
226  // init variables
227  //****************************************
228 
229  m_aFingerJointsInWorldCS.resize(5);
230  for (int i = 0; i < 5; i++)
231  {
232  m_aFingerJointsInWorldCS.at(i).resize(
233  m_aFingers.at(i)->m_aFingerJointsInFingerBaseCS.size());
234  for (size_t j = 0; j < m_aFingerJointsInWorldCS.at(i).size(); j++)
235  {
236  Math3d::SetVec(m_aFingerJointsInWorldCS.at(i).at(j), Math3d::zero_vec);
237  }
238  }
239 
241  for (int i = 0; i < 5; i++)
242  {
243  m_aFingerTipCornersInWorldCS.at(i).resize(
244  m_aFingers.at(i)->m_aFingerTipCornersInFingerBaseCS.size());
245  for (size_t j = 0; j < m_aFingerTipCornersInWorldCS.at(i).size(); j++)
246  {
247  Math3d::SetVec(m_aFingerTipCornersInWorldCS.at(i).at(j), Math3d::zero_vec);
248  }
249  }
250 
251  m_aFingerTipPolygonsLeftCam.resize(5);
253 
254  m_fPalmJointAngle = 0;
255  Math3d::SetVec(m_vHandPosition, Math3d::zero_vec);
256  Math3d::SetMat(m_mHandOrientation, Math3d::unit_mat);
257  }
258 
259  void
260  HandModeliCub::UpdateHand(double* pConfig)
261  {
262  Vec3d vHandPosition = {(float)pConfig[0], (float)pConfig[1], (float)pConfig[2]};
263  Mat3d mHandOrientation;
264  Math3d::SetRotationMat(mHandOrientation, pConfig[3], pConfig[4], pConfig[5]);
265 
266  float fPalmJointAngle = pConfig[6];
267 
268  std::vector<std::vector<float>> aFingerJointAngles;
269  aFingerJointAngles.resize(5);
270  aFingerJointAngles.at(0).push_back(pConfig[7]);
271  aFingerJointAngles.at(0).push_back(pConfig[8]);
272  aFingerJointAngles.at(0).push_back(pConfig[8]);
273  aFingerJointAngles.at(0).push_back(pConfig[8]);
274  aFingerJointAngles.at(1).push_back(-pConfig[9]);
275  aFingerJointAngles.at(1).push_back(-pConfig[9]);
276  aFingerJointAngles.at(1).push_back(-pConfig[9]);
277  aFingerJointAngles.at(2).push_back(-pConfig[10]);
278  aFingerJointAngles.at(2).push_back(-pConfig[10]);
279  aFingerJointAngles.at(2).push_back(-pConfig[10]);
280  aFingerJointAngles.at(3).push_back(-pConfig[11]);
281  aFingerJointAngles.at(3).push_back(-pConfig[11]);
282  aFingerJointAngles.at(3).push_back(-pConfig[11]);
283  aFingerJointAngles.at(4).push_back(-pConfig[11]);
284  aFingerJointAngles.at(4).push_back(-pConfig[11]);
285  aFingerJointAngles.at(4).push_back(-pConfig[11]);
286 
288  vHandPosition, mHandOrientation, fPalmJointAngle, aFingerJointAngles);
289  }
290 } // namespace visionx
visionx::CHandModelV2::CFinger
Definition: HandModelV2.h:39
GfxTL::Vec3d
VectorXD< 3, double > Vec3d
Definition: VectorXD.h:737
visionx
ArmarX headers.
Definition: OpenPoseStressTest.h:38
visionx::HandModeliCub::UpdateHand
void UpdateHand(double *pConfig) override
Definition: HandModeliCub.cpp:260
visionx::CHandModelV2::m_fPalmJointAngle
float m_fPalmJointAngle
Definition: HandModelV2.h:96
HandModeliCub.h
visionx::CHandModelV2::m_pStereoCalibration
CStereoCalibration * m_pStereoCalibration
Definition: HandModelV2.h:91
visionx::CHandModelV2::m_aFingerTipPolygonsRightCam
std::vector< ConvexPolygonCalculations::Polygon > m_aFingerTipPolygonsRightCam
Definition: HandModelV2.h:77
visionx::CHandModelV2::m_aFingers
std::vector< CFinger * > m_aFingers
Definition: HandModelV2.h:93
visionx::CHandModelV2::m_aFingerJointsInWorldCS
std::vector< std::vector< Vec3d > > m_aFingerJointsInWorldCS
Definition: HandModelV2.h:70
visionx::CHandModelV2::m_vTrackingBallOffset
Vec3d m_vTrackingBallOffset
Definition: HandModelV2.h:98
visionx::CHandModelV2::m_vHandPosition
Vec3d m_vHandPosition
Definition: HandModelV2.h:73
visionx::CHandModelV2::GetNextNonCommentLine
std::string GetNextNonCommentLine(std::ifstream &sFileStream)
Definition: HandModelV2.cpp:283
ARMARX_WARNING_S
#define ARMARX_WARNING_S
Definition: Logging.h:213
visionx::CHandModelV2::m_aFingerTipCornersInWorldCS
std::vector< std::vector< Vec3d > > m_aFingerTipCornersInWorldCS
Definition: HandModelV2.h:71
visionx::CHandModelV2::m_aOffsetsToFingers
std::vector< Vec3d > m_aOffsetsToFingers
Definition: HandModelV2.h:95
visionx::CHandModelV2::m_mHandOrientation
Mat3d m_mHandOrientation
Definition: HandModelV2.h:74
float
#define float
Definition: 16_Level.h:22
visionx::CHandModelV2::m_fTrackingBallRadius
float m_fTrackingBallRadius
Definition: HandModelV2.h:99
visionx::HandModeliCub::HandModeliCub
HandModeliCub(std::string sConfigFileName, CStereoCalibration *pStereoCalibration)
Definition: HandModeliCub.cpp:33
ARMARX_VERBOSE_S
#define ARMARX_VERBOSE_S
Definition: Logging.h:207
Logging.h
visionx::CHandModelV2::UpdateHand
virtual void UpdateHand(double *pConfig)
Definition: HandModelV2.cpp:394
visionx::CHandModelV2::m_aFingerTipPolygonsLeftCam
std::vector< ConvexPolygonCalculations::Polygon > m_aFingerTipPolygonsLeftCam
Definition: HandModelV2.h:76