javax.robotics.engine.clik
Class ClikJacobianPosInverse

java.lang.Object
  extended by javax.robotics.engine.clik.ClikJacobianPosInverse
All Implemented Interfaces:
CLIKR
Direct Known Subclasses:
ClikJacobianPosTranspose

public class ClikJacobianPosInverse
extends java.lang.Object
implements CLIKR

Closed Loop Inverse Kinematics with positional Jacobian inverse. The class implements the same scheme depicted in ClikJacobianInverse:
The inverse is computed using SVD decomposition:

J-1 = JT*(J*JT + λ2*I)-1
where λ2 is the damped factor equals 1 - (σr/ε)*λ2max if σr< ε, equals 0 if σr≥ ε; σr is the smallest not null singular value.

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

Since:
1.0.2
Version:
11/11/2005
Author:
Carmine Lia
See Also:
the solution without velocity constraint., the solution with velocity constraint.

Constructor Summary
ClikJacobianPosInverse(Robot robot, DMatrix Kp)
          Costructor with default sample time, dt = 1e-3 and eps = 0.02, lambdaMax=0.02, the space dimension = 3.
ClikJacobianPosInverse(Robot robot, DMatrix Kp, double dt, int spaceDim, double eps, double lambdaMax)
          Constructor.
ClikJacobianPosInverse(Robot robot, DMatrix Kp, int spaceDim)
          Costructor with default sample time, dt = 1e-3 and eps = 0.02, lambdaMax=0.02.
ClikJacobianPosInverse(Robot robot, DMatrix Kp, int spaceDim, double dt)
          Costructor with eps = 0.02, lambdaMax=0.02.
 
Method Summary
 int getCartesianSpaceDim()
          Gets the dimension of cartesian space.
 double getEps()
          Gets the singular region area.
 RVector getJointsPosition()
          Gets the current joints position.
 RVector getJointsVelocity()
          Gets the current joints velocity.
 DMatrix getKp()
          Gets the matrix of error position gain.
 double getLambdaMax()
          Gets the maximum damped factor.
 RVector3d getPositionError()
          Gets the current position error.
 double getSampleTime()
          Gets the sample time.
 void setEps(double eps)
          Sets the singular region area.
 void setKp(DMatrix kp)
          Sets the matrix of error position gain.
 void setLambdaMax(double lambdaMax)
          Sets the maximum damped factor.
 void setSampleTime(double h)
          Sets the sample time.
 void step(RVector pd, RVector ppd)
          Compute the joints position and velocity from a given desired end effector position and velocity.
 void step(RVector pd, RVector ppd, ConstraintVelocity constraint)
          Compute the joints position and velocity from a given desired end effector position and velocity with velocity constraint.
 
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
 

Constructor Detail

ClikJacobianPosInverse

public ClikJacobianPosInverse(Robot robot,
                              DMatrix Kp)
Costructor with default sample time, dt = 1e-3 and eps = 0.02, lambdaMax=0.02, the space dimension = 3.

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

ClikJacobianPosInverse

public ClikJacobianPosInverse(Robot robot,
                              DMatrix Kp,
                              int spaceDim)
Costructor with default sample time, dt = 1e-3 and eps = 0.02, lambdaMax=0.02.

Parameters:
robot - the robot.
Kp - the diagonal matrix of error position gain.
spaceDim - the dimension of robot operational space.

ClikJacobianPosInverse

public ClikJacobianPosInverse(Robot robot,
                              DMatrix Kp,
                              int spaceDim,
                              double dt)
Costructor with eps = 0.02, lambdaMax=0.02.

Parameters:
robot - the robot.
Kp - the diagonal matrix of error position gain.
spaceDim - the dimension of robot operational space.
dt - the sample time.

ClikJacobianPosInverse

public ClikJacobianPosInverse(Robot robot,
                              DMatrix Kp,
                              double dt,
                              int spaceDim,
                              double eps,
                              double lambdaMax)
Constructor.

Parameters:
robot - the robot.
Kp - the diagonal matrix of error position gain.
spaceDim - the dimension of robot operational space.
dt - the sample time.
eps - the area of singular region.
lambdaMax - the maximum of damped factor.
Method Detail

getCartesianSpaceDim

public final int getCartesianSpaceDim()
Description copied from interface: CLIKR
Gets the dimension of cartesian space. For planar robots the value is 2, the value is set from dimension of diagonal matrix gain Kp.

Specified by:
getCartesianSpaceDim in interface CLIKR
Returns:
the dimension value.

getEps

public final double getEps()
Description copied from interface: CLIKR
Gets the singular region area.

Specified by:
getEps in interface CLIKR
Returns:
the eps.

setEps

public final void setEps(double eps)
Description copied from interface: CLIKR
Sets the singular region area.

Specified by:
setEps in interface CLIKR
Parameters:
eps - The eps to set.

getSampleTime

public final double getSampleTime()
Description copied from interface: CLIKR
Gets the sample time.

Specified by:
getSampleTime in interface CLIKR
Returns:
the sample time.

setSampleTime

public final void setSampleTime(double h)
Description copied from interface: CLIKR
Sets the sample time.

Specified by:
setSampleTime in interface CLIKR
Parameters:
h - The sample time to set.

getKp

public final DMatrix getKp()
Description copied from interface: CLIKR
Gets the matrix of error position gain.

Specified by:
getKp in interface CLIKR
Returns:
the diagonal matrix.

setKp

public final void setKp(DMatrix kp)
Description copied from interface: CLIKR
Sets the matrix of error position gain. The matrix must be of dimension 2 for planar robots.

Specified by:
setKp in interface CLIKR
Parameters:
kp - The diagonal matrix to set.

getLambdaMax

public final double getLambdaMax()
Description copied from interface: CLIKR
Gets the maximum damped factor.

Specified by:
getLambdaMax in interface CLIKR
Returns:
the damped factor.

setLambdaMax

public final void setLambdaMax(double lambdaMax)
Description copied from interface: CLIKR
Sets the maximum damped factor.

Specified by:
setLambdaMax in interface CLIKR
Parameters:
lambdaMax - The damped factor to set.

getPositionError

public final RVector3d getPositionError()
Description copied from interface: CLIKR
Gets the current position error.

Specified by:
getPositionError in interface CLIKR
Returns:
the position error vector.

getJointsPosition

public final RVector getJointsPosition()
Gets the current joints position.

Specified by:
getJointsPosition in interface CLIKR
Returns:
the joints position vector.

getJointsVelocity

public final RVector getJointsVelocity()
Gets the current joints velocity.

Specified by:
getJointsVelocity in interface CLIKR
Returns:
the joints velocity vector.

step

public void step(RVector pd,
                 RVector ppd)
Compute the joints position and velocity from a given desired end effector position and velocity. The joints velocity is computed as:
q'=pinv(J)*(xd' +Ke)
the joints position is computed by Euler integration:
q(t+dt) = q(t) + q'(t)*dt;

Specified by:
step in interface CLIKR
Parameters:
pd - the RVector of desired end effector position.
ppd - the RVector of desired end effector velocity.

step

public void step(RVector pd,
                 RVector ppd,
                 ConstraintVelocity constraint)
Compute the joints position and velocity from a given desired end effector position and velocity with velocity constraint. The joints velocity is computed as:
q'=pinv(J)*(xd'
 +Ke)+(I-pinv(J)*J)*q0'
the joints position is computed by Euler integration:
q(t+dt) = q(t) + q'(t)*dt;

Specified by:
step in interface CLIKR
Parameters:
pd - the RVector of desired end effector position.
ppd - the RVector of desired end effector velocity.
constraint - the velocity constraint class.
See Also:
ConstraintVelocity