chainiksolverpos_nr_jl_coupling.cpp
Go to the documentation of this file.
1 // Copyright (C) 2007 Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
2 // Copyright (C) 2008 Mikael Mayer
3 // Copyright (C) 2008 Julia Jesse
4 
5 // Version: 1.0
6 // Author: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
7 // Maintainer: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
8 // URL: http://www.orocos.org/kdl
9 
10 // Modified by Juan A. Corrales (ISIR, UPMC) in order to include coupling
11 
12 // This library is free software; you can redistribute it and/or
13 // modify it under the terms of the GNU Lesser General Public
14 // License as published by the Free Software Foundation; either
15 // version 2.1 of the License, or (at your option) any later version.
16 
17 // This library is distributed in the hope that it will be useful,
18 // but WITHOUT ANY WARRANTY; without even the implied warranty of
19 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
20 // Lesser General Public License for more details.
21 
22 // You should have received a copy of the GNU Lesser General Public
23 // License along with this library; if not, write to the Free Software
24 // Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
25 
28 
29 namespace KDL
30 {
32  const JntArray &_q_max, ChainFkSolverPos &_fksolver,
33  ChainIkSolverVel &_iksolver,
34  unsigned int _maxiter, double _eps) :
35  chain(_chain), q_min(chain.getNrOfJoints()), q_max(chain.getNrOfJoints()), fksolver(_fksolver),
36  iksolver(_iksolver), delta_q(_chain.getNrOfJoints()),
37  maxiter(_maxiter), eps(_eps)
38  {
39  q_min = _q_min;
40  q_max = _q_max;
41  }
42 
43  int ChainIkSolverPos_NR_JL_coupling::CartToJnt(const JntArray &q_init, const Frame &p_in, JntArray &q_out)
44  {
45  q_out = q_init;
46  Twist delta_twist_temp;
47  unsigned int i;
48  for (i = 0; i < maxiter; i++)
49  {
50  fksolver.JntToCart(q_out, f);
51  delta_twist = diff(f, p_in);
52  delta_twist_temp = delta_twist;
53 
54  ChainIkSolverVel_wdls_coupling *iksolver_wdls;
55  iksolver_wdls = dynamic_cast<ChainIkSolverVel_wdls_coupling *> (&iksolver);
56  if (iksolver_wdls != NULL) // Verify Mx matrix if ik velocity solver is based on WDLS
57  {
58  Eigen::MatrixXd Mx = iksolver_wdls->getWeightTS();
59  // Remove the error of those components which are null in Mx matrix.
60  // This is usually used to neglect the error of one or several components of the pose.
61  // Thereby, a solution of 3D inverse kinematics (only position or only orientation) can be obtained.
62  if (Mx(0, 0) == 0.0)
63  {
64  delta_twist_temp.vel.x(0.0);
65  }
66  if (Mx(1, 1) == 0.0)
67  {
68  delta_twist_temp.vel.y(0.0);
69  }
70  if (Mx(2, 2) == 0.0)
71  {
72  delta_twist_temp.vel.z(0.0);
73  }
74  if (Mx(3, 3) == 0.0)
75  {
76  delta_twist_temp.rot.x(0.0);
77  }
78  if (Mx(4, 4) == 0.0)
79  {
80  delta_twist_temp.rot.y(0.0);
81  }
82  if (Mx(5, 5) == 0.0)
83  {
84  delta_twist_temp.rot.z(0.0);
85  }
86  }
87 
88  if (Equal(delta_twist_temp, Twist::Zero(), eps))
89  {
90  break;
91  }
92 
94  Add(q_out, delta_q, q_out);
95 
96  for (unsigned int j = 0; j < q_min.rows(); j++)
97  {
98  if (q_out(j) < q_min(j))
99  {
100  q_out(j) = q_min(j);
101  }
102  }
103 
104 
105  for (unsigned int j = 0; j < q_max.rows(); j++)
106  {
107  if (q_out(j) > q_max(j))
108  {
109  q_out(j) = q_max(j);
110  }
111  }
112  }
113 
114  if (i != maxiter)
115  {
116  return 0;
117  }
118  else
119  {
120  return -3;
121  }
122  }
123 
125  {
126  }
127 } // namespace KDL
128 
IMETHOD doubleVel diff(const doubleVel &a, const doubleVel &b, double dt=1.0)
static Twist Zero()
unsigned int rows() const
Vector vel
void Add(const JntArrayVel &src1, const JntArrayVel &src2, JntArrayVel &dest)
double z() const
virtual int CartToJnt(const JntArray &q_in, const Twist &v_in, JntArray &qdot_out)=0
IMETHOD bool Equal(const FrameAcc &r1, const FrameAcc &r2, double eps=epsilon)
ChainIkSolverPos_NR_JL_coupling(const Chain_coupling &chain, const JntArray &q_min, const JntArray &q_max, ChainFkSolverPos &fksolver, ChainIkSolverVel &iksolver, unsigned int maxiter=100, double eps=1e-6)
virtual int JntToCart(const JntArray &q_in, Frame &p_out, int segmentNr=-1)=0
Vector rot
double y() const
double x() const
virtual int CartToJnt(const JntArray &q_init, const Frame &p_in, JntArray &q_out)


kdl_coupling
Author(s): Juan Antonio Corrales Ramon (UPMC)
autogenerated on Wed Oct 14 2020 04:05:04