clik.h
Go to the documentation of this file.
1 /*
2 Copyright (C) 2002-2004 Etienne Lachance
3 
4 This library is free software; you can redistribute it and/or modify
5 it under the terms of the GNU Lesser General Public License as
6 published by the Free Software Foundation; either version 2.1 of the
7 License, or (at your option) any later version.
8 
9 This library is distributed in the hope that it will be useful,
10 but WITHOUT ANY WARRANTY; without even the implied warranty of
11 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 GNU Lesser General Public License for more details.
13 
14 You should have received a copy of the GNU Lesser General Public
15 License along with this library; if not, write to the Free Software
16 Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
17 
18 
19 Report problems and direct all questions to:
20 
21 email: etienne.lachance@polymtl.ca or richard.gourdeau@polymtl.ca
22 
23 Reference:
24 
25 CLIK: closed loop inverse kinematics
26 
27 [1] S. Chiaverini, B. Siciliano, "The Unit Quaternion: A Useful Tool for
28  Inverse Kinematics of Robot Manipulators", Systems Analysis, Modelling
29  and Simulation, vol. 35, pp.45-60, 1999.
30 
31 [2] F. Caccavale, S. Chiaverini, B. Siciliano, "Second-Order Kinematic Control
32  of Robot Manipulators with Jacobian Damped Least-Squares Inverse: Theory
33  and Experiments", IEEE/ASME Trans on Mechatronics, vol 2, no. 3,
34  pp. 188-194, 1997.
35 
36 [3] S. Chiaverini, B. Siciliano, "Review of the Damped Least-Squares Inverse
37  Kinematics with Experiments on an Industrial Robot Manipulator" IEEE Trans
38  on Control Systems Technology, vol 2, no 2, june 1994
39 
40 [4] C. Natale, "Quaternion-Based Representation of Rigid Bodies Orientation",
41  PRISMA LAB, PRISMA Technical Report no. 97-05, Oct 1997.
42 
43 The algorithme is based on [1], which is of first order.
44 
45 -------------------------------------------------------------------------------
46 Revision_history:
47 
48 2004/07/01: Etienne Lachance
49  -Added doxygen documentation.
50 
51 2004/07/01: Ethan Tira-Thompson
52  -Added support for newmat's use_namespace #define, using ROBOOP namespace
53 
54 2006/01/21: Etienne Lachance
55  -No need to include quaternion.h.
56 */
57 
58 
59 #ifndef CLIK_H
60 #define CLIK_H
61 
67 static const char header_clik_rcsid[] = "$Id: clik.h,v 1.6 2006/05/16 16:11:15 gourdeau Exp $";
69 
70 #include "robot.h"
71 
72 #ifdef use_namespace
73 namespace ROBOOP {
74  using namespace NEWMAT;
75 #endif
76 
77 
79 #define CLICK_DH 1
80 #define CLICK_mDH 2
82 #define CLICK_mDH_min_para 3
84 
85 
87 class Clik {
88 public:
89  Clik(){}
90  Clik(const Robot & robot_, const DiagonalMatrix & Kp_, const DiagonalMatrix & Ko_,
91  const Real eps_=0.04, const Real lambda_max_=0.04, const Real dt=1.0);
92  Clik(const mRobot & mrobot_, const DiagonalMatrix & Kp_, const DiagonalMatrix & Ko_,
93  const Real eps_=0.04, const Real lambda_max_=0.04, const Real dt=1.0);
94  Clik(const mRobot_min_para & mrobot_min_para_, const DiagonalMatrix & Kp_,
95  const DiagonalMatrix & Ko_, const Real eps_=0.04, const Real lambda_max_=0.04,
96  const Real dt=1.0);
97  Clik(const Clik & x);
98  ~Clik(){}
99  Clik & operator=(const Clik & x);
100  void q_qdot(const Quaternion & qd, const ColumnVector & pd,
101  const ColumnVector & pddot, const ColumnVector & wd,
102  ColumnVector & q, ColumnVector & qp);
103 private:
104  int endeff_pos_ori_err(const ColumnVector & pd, const ColumnVector & pddot,
105  const Quaternion & qd, const ColumnVector & wd);
106 
107  Real
108  dt,
109  eps,
110  lambda_max;
111  short robot_type;
116  Ko;
117 
119  qp,
120  qp_prev,
121  Kpep,
122  Koe0Quat,
123  v;
124 };
125 
126 #ifdef use_namespace
127 }
128 #endif
129 
130 #endif
Quaternion class definition.
Definition: quaternion.h:92
~Clik()
Definition: clik.h:98
Robot robot
Robot instance.
Definition: clik.h:112
mRobot mrobot
mRobot instance.
Definition: clik.h:113
static const char header_clik_rcsid[]
RCS/CVS version.
Definition: clik.h:68
DH notation robot class.
Definition: robot.h:340
Handle Closed Loop Inverse Kinematics scheme.
Definition: clik.h:87
Clik()
Definition: clik.h:89
Robots class definitions.
DiagonalMatrix Kp
Position error gain.
Definition: clik.h:115
double Real
Definition: include.h:307
Real lambda_max
Damping factor in Jacobian DLS inverse.
Definition: clik.h:108
ColumnVector v
Quaternion vector part.
Definition: clik.h:118
Modified DH notation robot class.
Definition: robot.h:389
Modified DH notation and minimal inertial parameters robot class.
Definition: robot.h:437
mRobot_min_para mrobot_min_para
mRobot_min_para instance.
Definition: clik.h:114
Diagonal matrix.
Definition: newmat.h:896
short robot_type
Robot type used.
Definition: clik.h:111
Column vector.
Definition: newmat.h:1008


kni
Author(s): Martin Günther
autogenerated on Fri Jun 7 2019 22:06:44