javax.robotics.engine.clik
Interface CLIK

All Known Implementing Classes:
ClikJacobianInverse, ClikJacobianTranspose

public interface CLIK

Closed Loop Inverse Kinematic algorithms interface for robots manipulator.

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

Method Summary
 double getEps()
          Gets the singular region area.
 RVector getJointsPosition()
          Gets the current joints position.
 RVector getJointsVelocity()
          Gets the current joints velocity.
 DMatrix getKo()
          Gets the matrix of error orientation gain.
 DMatrix getKp()
          Gets the matrix of error position gain.
 double getLambdaMax()
          Gets the maximum damped factor.
 RVector3d getOrientationError()
          Gets the current orientation error.
 RVector3d getPositionError()
          Gets the current position error.
 double getSampleTime()
          Gets the sample time.
 void setEps(double eps)
          Sets the singular region area.
 void setKo(DMatrix kd)
          Sets the matrix of error orientation gain.
 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(RVector3d pd, RVector3d ppd, Quaternion quatd, RVector3d wd)
          Compute the joints position and velocity from a given desired end effector position and orientation.
 

Method Detail

getEps

double getEps()
Gets the singular region area.

Returns:
the eps.

setEps

void setEps(double eps)
Sets the singular region area.

Parameters:
eps - The eps to set.

getSampleTime

double getSampleTime()
Gets the sample time.

Returns:
the sample time.

setSampleTime

void setSampleTime(double h)
Sets the sample time.

Parameters:
h - The sample time to set.

getKp

DMatrix getKp()
Gets the matrix of error position gain.

Returns:
the diagonal matrix.

setKp

void setKp(DMatrix kp)
Sets the matrix of error position gain.

Parameters:
kp - The diagonal matrix to set.

getKo

DMatrix getKo()
Gets the matrix of error orientation gain.

Returns:
the diagonal matrix.

setKo

void setKo(DMatrix kd)
Sets the matrix of error orientation gain.

Parameters:
kd - The diagonal matrix to set.

getLambdaMax

double getLambdaMax()
Gets the maximum damped factor.

Returns:
the damped factor.

setLambdaMax

void setLambdaMax(double lambdaMax)
Sets the maximum damped factor.

Parameters:
lambdaMax - The damped factor to set.

getPositionError

RVector3d getPositionError()
Gets the current position error.

Returns:
the position error vector.

getOrientationError

RVector3d getOrientationError()
Gets the current orientation error. The error is computed form quaternion as:

η(q)&epsilond - &etad&epsilon(q) - S(&epsilond)&epsilon(q)

where η and ε are the vector and the scalar components of quaternion respectively.

Returns:
the orientation error vector.

getJointsPosition

RVector getJointsPosition()
Gets the current joints position.

Returns:
the joints position vector.

getJointsVelocity

RVector getJointsVelocity()
Gets the current joints velocity.

Returns:
the joints velocity vector.

step

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.

Parameters:
pd - the vector of desired end effector position.
ppd - the vector of desired end effector velocity.
quatd - the desired end effector quaternion.
wd - the desired end effector angular velocity.