javax.robotics.engine.clik
Class ClikJacobianTranspose

java.lang.Object
  extended by javax.robotics.engine.clik.ClikJacobianInverse
      extended by javax.robotics.engine.clik.ClikJacobianTranspose
All Implemented Interfaces:
CLIK

public class ClikJacobianTranspose
extends ClikJacobianInverse

Closed Loop Inverse Kinematics with Jacobian transpose. The class implements this scheme:
CLIK scheme with transpose

The orientation error is computed as quaternion error.
The integration method used is the forward Euler.

Since:
1.0.2
Version:
11/11/2005
Author:
Carmine Lia

Constructor Summary
ClikJacobianTranspose(Robot robot, DMatrix Kp, DMatrix Ko)
          Costructor with default sample time, dt = 1e-3.
ClikJacobianTranspose(Robot robot, DMatrix Kp, DMatrix Ko, double dt)
          Costructor.
 
Method Summary
 void step(RVector3d pd, RVector3d ppd, Quaternion quatd, RVector3d wd)
          Compute the joints position and velocity from a given desired end effector position and orientation.
 
Methods inherited from class javax.robotics.engine.clik.ClikJacobianInverse
getEps, getJointsPosition, getJointsVelocity, getKo, getKp, getLambdaMax, getOrientationError, getPositionError, getSampleTime, setEps, setKo, setKp, setLambdaMax, setSampleTime
 
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
 

Constructor Detail

ClikJacobianTranspose

public ClikJacobianTranspose(Robot robot,
                             DMatrix Kp,
                             DMatrix Ko)
Costructor with default sample time, dt = 1e-3.

Parameters:
robot - the robot.
Kp - the diagonal matrix of error position gain.
Ko - the diagonal matrix of error orientationo gain.

ClikJacobianTranspose

public ClikJacobianTranspose(Robot robot,
                             DMatrix Kp,
                             DMatrix Ko,
                             double dt)
Costructor.

Parameters:
robot - the robot.
Kp - the diagonal matrix of error position gain.
Ko - the diagonal matrix of error orientationo gain.
dt - the sample time.
Method Detail

step

public void step(RVector3d pd,
                 RVector3d ppd,
                 Quaternion quatd,
                 RVector3d wd)
Compute the joints position and velocity from a given desired end effector position and orientation. The joints velocity is computed as:
q'=trans(J)*(K*e)
the joints position is computed by Euler integration:
q(t+dt) = q(t) + q'(t)*dt;

Specified by:
step in interface CLIK
Overrides:
step in class ClikJacobianInverse
Parameters:
pd - the vector of desired end effector position.
ppd - input parameter not considered.
quatd - the desired end effector quaternion.
wd - input parameter not considered.