-
Notifications
You must be signed in to change notification settings - Fork 442
Expand file tree
/
Copy pathchainiksolverpos_lma.cpp
More file actions
324 lines (292 loc) · 10.1 KB
/
chainiksolverpos_lma.cpp
File metadata and controls
324 lines (292 loc) · 10.1 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
/**
\file chainiksolverpos_lma.cpp
\brief computing inverse position kinematics using Levenberg-Marquardt.
*/
/**************************************************************************
begin : May 2012
copyright : (C) 2012 Erwin Aertbelien
email : firstname.lastname@mech.kuleuven.ac.be
History (only major changes)( AUTHOR-Description ) :
***************************************************************************
* This library is free software; you can redistribute it and/or *
* modify it under the terms of the GNU Lesser General Public *
* License as published by the Free Software Foundation; either *
* version 2.1 of the License, or (at your option) any later version. *
* *
* This library is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU *
* Lesser General Public License for more details. *
* *
* You should have received a copy of the GNU Lesser General Public *
* License along with this library; if not, write to the Free Software *
* Foundation, Inc., 59 Temple Place, *
* Suite 330, Boston, MA 02111-1307 USA *
* *
***************************************************************************/
#include "chainiksolverpos_lma.hpp"
#include <iostream>
namespace KDL {
template <typename Derived>
inline void Twist_to_Eigen(const KDL::Twist& t,Eigen::MatrixBase<Derived>& e) {
e(0)=t.vel.data[0];
e(1)=t.vel.data[1];
e(2)=t.vel.data[2];
e(3)=t.rot.data[0];
e(4)=t.rot.data[1];
e(5)=t.rot.data[2];
}
ChainIkSolverPos_LMA::ChainIkSolverPos_LMA(
const KDL::Chain& _chain,
const Eigen::Matrix<double,6,1>& _l,
double _eps,
int _maxiter,
double _eps_joints
) :
chain(_chain),
nj(chain.getNrOfJoints()),
ns(chain.getNrOfSegments()),
lastNrOfIter(0),
lastDifference(0),
lastTransDiff(0),
lastRotDiff(0),
lastSV(nj),
jac(6, nj),
grad(nj),
display_information(false),
maxiter(_maxiter),
eps(_eps),
eps_joints(_eps_joints),
L(_l.cast<ScalarType>()),
T_base_jointroot(nj),
T_base_jointtip(nj),
q(nj),
A(nj, nj),
tmp(nj),
ldlt(nj),
svd(6, nj,Eigen::ComputeThinU | Eigen::ComputeThinV),
diffq(nj),
q_new(nj),
original_Aii(nj)
{}
ChainIkSolverPos_LMA::ChainIkSolverPos_LMA(
const KDL::Chain& _chain,
double _eps,
int _maxiter,
double _eps_joints
) :
chain(_chain),
nj(chain.getNrOfJoints()),
ns(chain.getNrOfSegments()),
lastNrOfIter(0),
lastDifference(0),
lastTransDiff(0),
lastRotDiff(0),
lastSV(nj>6?6:nj),
jac(6, nj),
grad(nj),
display_information(false),
maxiter(_maxiter),
eps(_eps),
eps_joints(_eps_joints),
T_base_jointroot(nj),
T_base_jointtip(nj),
q(nj),
A(nj, nj),
ldlt(nj),
svd(6, nj,Eigen::ComputeThinU | Eigen::ComputeThinV),
diffq(nj),
q_new(nj),
original_Aii(nj)
{
L(0)=1;
L(1)=1;
L(2)=1;
L(3)=0.01;
L(4)=0.01;
L(5)=0.01;
}
void ChainIkSolverPos_LMA::updateInternalDataStructures() {
nj = chain.getNrOfJoints();
ns = chain.getNrOfSegments();
lastSV.conservativeResize(nj>6?6:nj);
jac.conservativeResize(Eigen::NoChange, nj);
grad.conservativeResize(nj);
T_base_jointroot.resize(nj);
T_base_jointtip.resize(nj);
q.conservativeResize(nj);
A.conservativeResize(nj, nj);
ldlt = Eigen::LDLT<MatrixXq>(nj);
svd = Eigen::JacobiSVD<MatrixXq>(6, nj,Eigen::ComputeThinU | Eigen::ComputeThinV);
diffq.conservativeResize(nj);
q_new.conservativeResize(nj);
original_Aii.conservativeResize(nj);
}
ChainIkSolverPos_LMA::~ChainIkSolverPos_LMA() {}
void ChainIkSolverPos_LMA::compute_fwdpos(const VectorXq& q) {
using namespace KDL;
unsigned int jointndx=0;
T_base_head = Frame::Identity(); // frame w.r.t. base of head
for (unsigned int i=0;i<chain.getNrOfSegments();i++) {
const Segment& segment = chain.getSegment(i);
if (segment.getJoint().getType()!=Joint::Fixed) {
T_base_jointroot[jointndx] = T_base_head;
T_base_head = T_base_head * segment.pose(q(jointndx));
T_base_jointtip[jointndx] = T_base_head;
jointndx++;
} else {
T_base_head = T_base_head * segment.pose(0.0);
}
}
}
void ChainIkSolverPos_LMA::compute_jacobian(const VectorXq& q) {
using namespace KDL;
unsigned int jointndx=0;
for (unsigned int i=0;i<chain.getNrOfSegments();i++) {
const Segment& segment = chain.getSegment(i);
if (segment.getJoint().getType()!=Joint::Fixed) {
// compute twist of the end effector motion caused by joint [jointndx]; expressed in base frame, with vel. ref. point equal to the end effector
KDL::Twist t = ( T_base_jointroot[jointndx].M * segment.twist(q(jointndx),1.0) ).RefPoint( T_base_head.p - T_base_jointtip[jointndx].p);
jac(0,jointndx)=t[0];
jac(1,jointndx)=t[1];
jac(2,jointndx)=t[2];
jac(3,jointndx)=t[3];
jac(4,jointndx)=t[4];
jac(5,jointndx)=t[5];
jointndx++;
}
}
}
void ChainIkSolverPos_LMA::display_jac(const KDL::JntArray& jval) {
VectorXq q;
q = jval.data.cast<ScalarType>();
compute_fwdpos(q);
compute_jacobian(q);
svd.compute(jac);
std::cout << "Singular values : " << svd.singularValues().transpose()<<"\n";
}
int ChainIkSolverPos_LMA::CartToJnt(const KDL::JntArray& q_init, const KDL::Frame& T_base_goal, KDL::JntArray& q_out) {
if (nj != chain.getNrOfJoints())
return (error = E_NOT_UP_TO_DATE);
if (nj != q_init.rows() || nj != q_out.rows())
return (error = E_SIZE_MISMATCH);
using namespace KDL;
double v = 2;
double tau = 10;
double rho;
double lambda;
Twist t;
double delta_pos_norm;
Eigen::Matrix<ScalarType,6,1> delta_pos;
Eigen::Matrix<ScalarType,6,1> delta_pos_new;
q=q_init.data.cast<ScalarType>();
compute_fwdpos(q);
Twist_to_Eigen( diff( T_base_head, T_base_goal), delta_pos );
delta_pos=L.asDiagonal()*delta_pos;
delta_pos_norm = delta_pos.norm();
if (delta_pos_norm<eps) {
lastNrOfIter =0 ;
Twist_to_Eigen( diff( T_base_head, T_base_goal), delta_pos );
lastDifference = delta_pos.norm();
lastTransDiff = delta_pos.topRows(3).norm();
lastRotDiff = delta_pos.bottomRows(3).norm();
svd.compute(jac);
original_Aii = svd.singularValues();
lastSV = svd.singularValues();
q_out.data = q.cast<double>();
return (error = E_NOERROR);
}
compute_jacobian(q);
jac = L.asDiagonal()*jac;
lambda = tau;
double dnorm = 1;
for (unsigned int i=0;i<maxiter;++i) {
svd.compute(jac);
original_Aii = svd.singularValues();
for (unsigned int j=0;j<original_Aii.rows();++j) {
original_Aii(j) = original_Aii(j)/( original_Aii(j)*original_Aii(j)+lambda);
}
tmp = svd.matrixU().transpose()*delta_pos;
tmp = original_Aii.cwiseProduct(tmp);
diffq = svd.matrixV()*tmp;
grad = jac.transpose()*delta_pos;
if (display_information) {
std::cout << "------- iteration " << i << " ----------------\n"
<< " q = " << q.transpose() << "\n"
<< " weighted jac = \n" << jac << "\n"
<< " lambda = " << lambda << "\n"
<< " eigenvalues = " << svd.singularValues().transpose() << "\n"
<< " difference = " << delta_pos.transpose() << "\n"
<< " difference norm= " << delta_pos_norm << "\n"
<< " proj. on grad. = " << grad << "\n";
std::cout << std::endl;
}
dnorm = diffq.lpNorm<Eigen::Infinity>();
if (dnorm < eps_joints) {
lastDifference = delta_pos_norm;
lastNrOfIter = i;
lastSV = svd.singularValues();
q_out.data = q.cast<double>();
compute_fwdpos(q);
Twist_to_Eigen( diff( T_base_head, T_base_goal), delta_pos );
lastTransDiff = delta_pos.topRows(3).norm();
lastRotDiff = delta_pos.bottomRows(3).norm();
return (error = E_INCREMENT_JOINTS_TOO_SMALL);
}
if (grad.transpose()*grad < eps_joints*eps_joints ) {
compute_fwdpos(q);
Twist_to_Eigen( diff( T_base_head, T_base_goal), delta_pos );
lastDifference = delta_pos_norm;
lastTransDiff = delta_pos.topRows(3).norm();
lastRotDiff = delta_pos.bottomRows(3).norm();
lastSV = svd.singularValues();
lastNrOfIter = i;
q_out.data = q.cast<double>();
return (error = E_GRADIENT_JOINTS_TOO_SMALL);
}
q_new = q+diffq;
compute_fwdpos(q_new);
Twist_to_Eigen( diff( T_base_head, T_base_goal), delta_pos_new );
delta_pos_new = L.asDiagonal()*delta_pos_new;
double delta_pos_new_norm = delta_pos_new.norm();
rho = delta_pos_norm*delta_pos_norm - delta_pos_new_norm*delta_pos_new_norm;
rho /= diffq.transpose()*(lambda*diffq + grad);
if (rho > 0) {
q = q_new;
delta_pos = delta_pos_new;
delta_pos_norm = delta_pos_new_norm;
if (delta_pos_norm<eps) {
Twist_to_Eigen( diff( T_base_head, T_base_goal), delta_pos );
lastDifference = delta_pos_norm;
lastTransDiff = delta_pos.topRows(3).norm();
lastRotDiff = delta_pos.bottomRows(3).norm();
lastSV = svd.singularValues();
lastNrOfIter = i;
q_out.data = q.cast<double>();
return (error = E_NOERROR);
}
compute_jacobian(q_new);
jac = L.asDiagonal()*jac;
double tmp=2*rho-1;
lambda = lambda*max(1/3.0, 1-tmp*tmp*tmp);
v = 2;
} else {
lambda = lambda*v;
v = 2*v;
}
}
lastDifference = delta_pos_norm;
lastTransDiff = delta_pos.topRows(3).norm();
lastRotDiff = delta_pos.bottomRows(3).norm();
lastSV = svd.singularValues();
lastNrOfIter = maxiter;
q_out.data = q.cast<double>();
return (error = E_MAX_ITERATIONS_EXCEEDED);
}
const char* ChainIkSolverPos_LMA::strError(const int error) const
{
if (E_GRADIENT_JOINTS_TOO_SMALL == error) return "The gradient of E towards the joints is to small";
else if (E_INCREMENT_JOINTS_TOO_SMALL == error) return "The joint position increments are to small";
else return SolverI::strError(error);
}
}//namespace KDL