javax.robotics.engine.clik
Interface CLIKR

All Known Implementing Classes:
ClikJacobianPosInverse, ClikJacobianPosTranspose

public interface CLIKR

Closed Loop Inverse Kinematic algorithms interface for redundant robots manipulator.

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

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 c)
          Compute the joints position and velocity from a given desired end effector position and velocity with velocity constraints.
 

Method Detail

getCartesianSpaceDim

int getCartesianSpaceDim()
Gets the dimension of cartesian space. For planar robots the value is 2, the value is set from dimension of diagonal matrix gain Kp.

Returns:
the dimension value.

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. The matrix must be of dimension 2 for planar robots.

Parameters:
kp - 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.

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(RVector pd,
          RVector ppd)
Compute the joints position and velocity from a given desired end effector position and velocity.

Parameters:
pd - the vector of desired end effector position.
ppd - the vector of desired end effector velocity.

step

void step(RVector pd,
          RVector ppd,
          ConstraintVelocity c)
Compute the joints position and velocity from a given desired end effector position and velocity with velocity constraints.

Parameters:
pd - the vector of desired end effector position.
ppd - the vector of desired end effector velocity.
c - the velocity constraint class.
See Also:
ConstraintVelocity