Clik Class Reference
Handle Closed Loop Inverse Kinematics scheme.
More...
#include <clik.h>
List of all members.
Public Member Functions |
| Clik (const Clik &x) |
| Copy constructor.
|
| Clik (const mRobot_min_para &mrobot_min_para_, const DiagonalMatrix &Kp_, const DiagonalMatrix &Ko_, const Real eps_=0.04, const Real lambda_max_=0.04, const Real dt=1.0) |
| Constructor.
|
| Clik (const mRobot &mrobot_, const DiagonalMatrix &Kp_, const DiagonalMatrix &Ko_, const Real eps_=0.04, const Real lambda_max_=0.04, const Real dt=1.0) |
| Constructor.
|
| Clik (const Robot &robot_, const DiagonalMatrix &Kp_, const DiagonalMatrix &Ko_, const Real eps_=0.04, const Real lambda_max_=0.04, const Real dt=1.0) |
| Constructor.
|
| Clik () |
Clik & | operator= (const Clik &x) |
| Overload = operator.
|
void | q_qdot (const Quaternion &qd, const ColumnVector &pd, const ColumnVector &pddot, const ColumnVector &wd, ColumnVector &q, ColumnVector &qp) |
| Obtain joints position and velocity.
|
| ~Clik () |
Private Member Functions |
int | endeff_pos_ori_err (const ColumnVector &pd, const ColumnVector &pddot, const Quaternion &qd, const ColumnVector &wd) |
| Obtain end effector position and orientation error.
|
Private Attributes |
Real | dt |
| Time frame.
|
Real | eps |
| Range of singular region in Jacobian DLS inverse.
|
DiagonalMatrix | Ko |
| Orientation error gain.
|
ColumnVector | Koe0Quat |
| Ko times orientation error (quaternion vector part).
|
DiagonalMatrix | Kp |
| Position error gain.
|
ColumnVector | Kpep |
| Kp times position error.
|
Real | lambda_max |
| Damping factor in Jacobian DLS inverse.
|
mRobot | mrobot |
| mRobot instance.
|
mRobot_min_para | mrobot_min_para |
| mRobot_min_para instance.
|
ColumnVector | q |
| Clik joint position.
|
ColumnVector | qp |
| Clik joint velocity.
|
ColumnVector | qp_prev |
| Clik previous joint velocity.
|
Robot | robot |
| Robot instance.
|
short | robot_type |
| Robot type used.
|
ColumnVector | v |
| Quaternion vector part.
|
Detailed Description
Handle Closed Loop Inverse Kinematics scheme.
Definition at line 87 of file clik.h.
Constructor & Destructor Documentation
Clik::Clik |
( |
const Robot & |
robot_, |
|
|
const DiagonalMatrix & |
Kp_, |
|
|
const DiagonalMatrix & |
Ko_, |
|
|
const Real |
eps_ = 0.04 , |
|
|
const Real |
lambda_max_ = 0.04 , |
|
|
const Real |
dt = 1.0 | |
|
) |
| | |
Constructor.
Definition at line 53 of file clik.cpp.
Constructor.
Definition at line 91 of file clik.cpp.
Clik::Clik |
( |
const Clik & |
x |
) |
|
Copy constructor.
Definition at line 163 of file clik.cpp.
Member Function Documentation
Obtain end effector position and orientation error.
- Parameters:
-
| pd,: | Desired eff position in base frame. |
| pdd,: | Desired eff velocity in base frame. |
| qqqd,: | Desired eff orientation in base frame. |
| wd,: | Desired eff angular velocity in base frame. |
Definition at line 224 of file clik.cpp.
Clik & Clik::operator= |
( |
const Clik & |
x |
) |
|
Overload = operator.
Definition at line 192 of file clik.cpp.
Obtain joints position and velocity.
- Parameters:
-
| qd,: | Desired eff orientatio in base frame. |
| pd,: | Desired eff position in base frame. |
| pdd,: | Desired eff velocity in base frame. |
| wd,: | Desired eff angular velocity in base frame. |
| q_,: | Output joint position. |
| qp_,: | Output joint velocity. |
Definition at line 269 of file clik.cpp.
Member Data Documentation
Time frame.
Definition at line 108 of file clik.h.
Range of singular region in Jacobian DLS inverse.
Definition at line 108 of file clik.h.
Orientation error gain.
Definition at line 115 of file clik.h.
Ko times orientation error (quaternion vector part).
Definition at line 118 of file clik.h.
Position error gain.
Definition at line 115 of file clik.h.
Kp times position error.
Definition at line 118 of file clik.h.
Clik previous joint velocity.
Definition at line 118 of file clik.h.
The documentation for this class was generated from the following files: