chainiksolvervel_wdls_coupling.hpp
Go to the documentation of this file.
1 // Copyright (C) 2007 Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
2 
3 // Version: 1.0
4 // Author: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
5 // Maintainer: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
6 // URL: http://www.orocos.org/kdl
7 
8 // Modified by Juan A. Corrales (ISIR, UPMC) in order to include coupling
9 
10 // This library is free software; you can redistribute it and/or
11 // modify it under the terms of the GNU Lesser General Public
12 // License as published by the Free Software Foundation; either
13 // version 2.1 of the License, or (at your option) any later version.
14 
15 // This library is distributed in the hope that it will be useful,
16 // but WITHOUT ANY WARRANTY; without even the implied warranty of
17 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
18 // Lesser General Public License for more details.
19 
20 // You should have received a copy of the GNU Lesser General Public
21 // License along with this library; if not, write to the Free Software
22 // Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
23 
24 #ifndef KDL_CHAIN_IKSOLVERVEL_WDLS_COUPLING_HPP
25 #define KDL_CHAIN_IKSOLVERVEL_WDLS_COUPLING_HPP
26 
27 #include <kdl/chainiksolver.hpp>
30 #include <Eigen/Core>
31 
32 namespace KDL
33 {
34 /*
35 * Implementation of a inverse velocity kinematics algorithm based
36 * on the weighted pseudo inverse with damped least-square to calculate the velocity
37 * transformation from Cartesian to joint space of a general
38 * KDL::Chain. It uses a svd-calculation based on householders
39 * rotations.
40 *
41 * J# = M_q*Vb*pinv_dls(Db)*Ub'*M_x
42 *
43 * where B = Mx*J*Mq
44 *
45 * and B = Ub*Db*Vb' is the SVD decomposition of B
46 *
47 * Mq and Mx represent, respectively, the joint-space and task-space weighting
48 * matrices.
49 * Please refer to the documentation of setWeightJS(const Eigen::MatrixXd& Mq)
50 * and setWeightTS(const Eigen::MatrixXd& Mx) for details on the effects of
51 * these matrices.
52 *
53 * For more details on Weighted Pseudo Inverse, see :
54 * 1) [Ben Israel 03] A. Ben Israel & T.N.E. Greville.
55 * Generalized Inverses : Theory and Applications,
56 * second edition. Springer, 2003. ISBN 0-387-00293-6.
57 *
58 * 2) [Doty 93] K. L. Doty, C. Melchiorri & C. Boniveto.
59 * A theory of generalized inverses applied to Robotics.
60 * The International Journal of Robotics Research,
61 * vol. 12, no. 1, pages 1-19, february 1993.
62 *
63 *
64 * @ingroup KinematicFamily
65 */
67  public ChainIkSolverVel
68 {
69 public:
70  /*
71  * Constructor of the solver
72  *
73  * @param chain the chain to calculate the inverse velocity
74  * kinematics for
75  * @param eps if a singular value is below this value, its
76  * inverse is set to zero, default: 0.00001
77  * @param maxiter maximum iterations for the svd calculation,
78  * default: 150
79  *
80  */
81 
82  explicit ChainIkSolverVel_wdls_coupling(const Chain_coupling &chain, double eps = 0.00001, int maxiter = 150);
83 
84  // =ublas::identity_matrix<double>
86 
87  virtual int CartToJnt(const JntArray &q_in, const Twist &v_in, JntArray &qdot_out);
88 
89  /*
90  * not (yet) implemented.
91  *
92  */
93  virtual int CartToJnt(const JntArray &q_init, const FrameVel &v_in, JntArrayVel &q_out)
94  {
95  return -1;
96  };
97 
98  /*
99  * Set the joint space weighting matrix
100  *
101  * @param weight_js joint space weighting symetric matrix,
102  * default : identity. M_q : This matrix being used as a
103  * weight for the norm of the joint space speed it HAS TO BE
104  * symmetric and positive definite. We can actually deal with
105  * matrices containing a symmetric and positive definite block
106  * and 0s otherwise. Taking a diagonal matrix as an example, a
107  * 0 on the diagonal means that the corresponding joints will
108  * not contribute to the motion of the system. On the other
109  * hand, the bigger the value, the most the corresponding
110  * joint will contribute to the overall motion. The obtained
111  * solution q_dot will actually minimize the weighted norm
112  * sqrt(q_dot'*(M_q^-2)*q_dot). In the special case we deal
113  * with, it does not make sense to invert M_q but what is
114  * important is the physical meaning of all this : a joint
115  * that has a zero weight in M_q will not contribute to the
116  * motion of the system and this is equivalent to saying that
117  * it gets an infinite weight in the norm computation. For
118  * more detailed explanation : vincent.padois@upmc.fr
119  */
120  void setWeightJS(const Eigen::MatrixXd &Mq);
121 
122  Eigen::MatrixXd getWeightJS();
123 
124  /*
125  * Set the task space weighting matrix
126  *
127  * @param weight_ts task space weighting symetric matrix,
128  * default: identity M_x : This matrix being used as a weight
129  * for the norm of the error (in terms of task space speed) it
130  * HAS TO BE symmetric and positive definite. We can actually
131  * deal with matrices containing a symmetric and positive
132  * definite block and 0s otherwise. Taking a diagonal matrix
133  * as an example, a 0 on the diagonal means that the
134  * corresponding task coordinate will not be taken into
135  * account (ie the corresponding error can be really big). If
136  * the rank of the jacobian is equal to the number of task
137  * space coordinates which do not have a 0 weight in M_x, the
138  * weighting will actually not impact the results (ie there is
139  * an exact solution to the velocity inverse kinematics
140  * problem). In cases without an exact solution, the bigger
141  * the value, the most the corresponding task coordinate will
142  * be taken into account (ie the more the corresponding error
143  * will be reduced). The obtained solution will minimize the
144  * weighted norm sqrt(|x_dot-Jq_dot|'*(M_x^2)*|x_dot-Jq_dot|).
145  * For more detailed explanation : vincent.padois@upmc.fr
146  */
147  void setWeightTS(const Eigen::MatrixXd &Mx);
148 
149  Eigen::MatrixXd getWeightTS();
150 
151  void setLambda(const double &lambda);
152 
153 private:
157  Eigen::MatrixXd U;
158  Eigen::VectorXd S;
159  Eigen::MatrixXd V;
160  double eps;
161  int maxiter;
162  Eigen::VectorXd tmp;
163  Eigen::MatrixXd tmp_jac;
164  Eigen::MatrixXd tmp_jac_weight1;
165  Eigen::MatrixXd tmp_jac_weight2;
166  Eigen::MatrixXd tmp_ts;
167  Eigen::MatrixXd tmp_js;
168  Eigen::MatrixXd weight_ts;
169  Eigen::MatrixXd weight_js;
170  double lambda;
171 };
172 } // namespace KDL
173 #endif
174 
virtual int CartToJnt(const JntArray &q_init, const FrameVel &v_in, JntArrayVel &q_out)
ChainIkSolverVel_wdls_coupling(const Chain_coupling &chain, double eps=0.00001, int maxiter=150)
virtual int CartToJnt(const JntArray &q_in, const Twist &v_in, JntArray &qdot_out)


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