javax.robotics.engine.robots
Interface Robot

All Superinterfaces:
java.io.Serializable
All Known Subinterfaces:
Robot3D
All Known Implementing Classes:
DHRobot, DHRobot3D

public interface Robot
extends java.io.Serializable

This is an interface for kinematics and dynamics model of different open chain robot manipulators.

Example of use

The example Demo.java shows how to use Robot class in your java based application.

Since:
1.0.0
Version:
16/11/2005
Author:
Carmine Lia

Field Summary
static boolean DEBUG
           
static int HOMOGENEOUS_MATRIX_DIM
           
static int INITMOTOR_DIM
           
static int INITROBOT_DIM
           
static int JACOBIAN_DIMENSION
           
static int SPACE_DIM
           
 
Method Summary
 RVector acceleration(double[] q, double[] qp, double[] tau)
          Computes the solution of the Forward Dynamics Problem.
 RVector acceleration(double[] q, double[] qp, double[] tauCmd, double[] Fext, double[] Next)
          Computes the solution of the Forward Dynamics Problem with load applied to the last link.
 RVector acceleration(RVector q, RVector qp, RVector tau)
          Computes the solution of the Forward Dynamics Problem.
 RVector acceleration(RVector q, RVector qp, RVector tauCmd, RVector3d Fext, RVector3d Next)
          Computes the solution of the Forward Dynamics Problem with load applied to the last link.
 RMatrix4d dTdqi(int j)
          Computes the partial derivative of homogeneous transform respect j-th joint.
 int getAvailableDof()
          Gets the available degrees of freedom of robot.
 int getDof()
          Gets the degrees of freedom of robot.
 RVector3d getGravity()
          Gets gravity vector.
 short getID()
          Gets Robot class ID
 RVector getQ()
          Gets joints position.
 double getQ(int i)
          Position of i-th joint.
 RVector getQMax()
          Gets joints maximum position.
 RVector getQMin()
          Gets joints minimum position.
 RVector getQOffset()
          Gets joints offset position.
 RVector getQp()
          Gets joints velocity.
 RVector getQpp()
          Gets joints acceleration.
 XmlRobot getRobotConfiguration()
          Gets the robot configuration.
 Matrix inertia(RVector q)
          Computes the inertia matrix.
 RVector invKine(RMatrix4d Tobj)
          Computes the solution of the Inverse Kinematics Problem from homogeneous transform matrix using a Newton-Raphson technique.
 RVector invKine(RMatrix4d Tobj, int mj, int endlink)
          Computes the solution of the Inverse Kinematics Problem from homogeneous transform matrix using a Newton-Raphson or Taylor expansion techniques.
 Matrix jacobian()
          Computes the Jacobian matrix expressed in the base frame.
 Matrix jacobian(int ref)
          Computes the Jacobian matrix expressed in the ref-th frame.
 Matrix jacobianDLSinv(double eps, double lambdaMax)
          Computes the 6x6 inverse Jacobian matrix based on the Damped Least-Squares scheme.
 Matrix jacobianDot()
          Computes the Jacobian time derivative matrix expressed in the base frame.
 Matrix jacobianDot(int ref)
          Computes the Jacobian time derivative matrix expressed in the ref-th frame.
 RMatrix4d kine()
          Computes the solution of the Forward Kinematics Problem.
 RMatrix4d kine(int j)
          Computes the solution of the Forward Kinematics Problem for the link j.
 void setGravity(RVector3d g)
          Sets the gravity vector.
 void setQ(double[] q)
          Sets joints position.
 void setQ(double q, int i)
          Sets the position pf i-th joint position.
 void setQ(RVector q)
          Sets joints position.
 void setQp(double[] qp)
          Sets joints velocity.
 void setQp(RVector qp)
          Sets joints velocity.
 void setQpp(double[] qpp)
          Sets joints acceleration.
 void setQpp(RVector qpp)
          Sets joints acceleration.
 RVector torque(double[] q, double[] qp, double[] qpp)
          Computes the solution of the Inverse Dynamics Problem.
 RVector torque(double[] q, double[] qp, double[] qpp, double[] Fext, double[] Next)
          Computes the solution of the Inverse Dynamics Problem with load applied to the last link.
 RVector torque(RVector q, RVector qp, RVector qpp)
          Computes the solution of the Inverse Dynamics Problem.
 RVector torque(RVector q, RVector qp, RVector qpp, RVector3d Fext, RVector3d Next)
          Computes the solution of the Inverse Dynamics Problem with load applied to the last link.
 RVector torqueC(RVector qp)
          Computes the torques from the Coriolis and centrifugal effect.
 RVector torqueCoulombFriction(RVector qp)
          Computes the torques from the Coulomb friction.
 RVector torqueGravity()
          Computes the torques from the gravity effect.
 RVector torqueViscousFriction(RVector qp)
          Computes the torques from the viscous friction.
 

Field Detail

DEBUG

static final boolean DEBUG
See Also:
Constant Field Values

INITROBOT_DIM

static final int INITROBOT_DIM
See Also:
Constant Field Values

INITMOTOR_DIM

static final int INITMOTOR_DIM
See Also:
Constant Field Values

JACOBIAN_DIMENSION

static final int JACOBIAN_DIMENSION
See Also:
Constant Field Values

HOMOGENEOUS_MATRIX_DIM

static final int HOMOGENEOUS_MATRIX_DIM
See Also:
Constant Field Values

SPACE_DIM

static final int SPACE_DIM
See Also:
Constant Field Values
Method Detail

getID

short getID()
Gets Robot class ID

Returns:
ID

getRobotConfiguration

XmlRobot getRobotConfiguration()
Gets the robot configuration.

Returns:
the robot configuration.

getDof

int getDof()
Gets the degrees of freedom of robot.

Returns:
degrees of freedom of robot manipulator

getAvailableDof

int getAvailableDof()
Gets the available degrees of freedom of robot.

Returns:
the available degrees of freedom of robot manipulator

getQMax

RVector getQMax()
Gets joints maximum position.

Returns:
vector of joints maximum position.

getQMin

RVector getQMin()
Gets joints minimum position.

Returns:
vector of joints minimum position.

getQOffset

RVector getQOffset()
Gets joints offset position.

Returns:
vector of joints offset position.

getQ

RVector getQ()
Gets joints position. The position is computed subtracting the offset.

Returns:
vector of joints position.

getQ

double getQ(int i)
Position of i-th joint. The position is computed subtracting the offset.

Parameters:
i - joint
Returns:
joint position.

getQp

RVector getQp()
Gets joints velocity.

Returns:
vector of joints velocity

getQpp

RVector getQpp()
Gets joints acceleration.

Returns:
vector of joints acceleration

setQ

void setQ(RVector q)
Sets joints position. The position is computed adding the offset.

Parameters:
q - vector of joints position

setQ

void setQ(double[] q)
Sets joints position. The position is computed adding the offset.

Parameters:
q - vector of joints position

setQ

void setQ(double q,
          int i)
Sets the position pf i-th joint position. The position is computed adding the offset.

Parameters:
q - joint position
i - joint

setQp

void setQp(RVector qp)
Sets joints velocity.

Parameters:
qp - vector of joints velocity

setQp

void setQp(double[] qp)
Sets joints velocity.

Parameters:
qp - array of joints velocity

setQpp

void setQpp(RVector qpp)
Sets joints acceleration.

Parameters:
qpp - vector of joints position

setQpp

void setQpp(double[] qpp)
Sets joints acceleration.

Parameters:
qpp - the array of joints position

invKine

RVector invKine(RMatrix4d Tobj)
Computes the solution of the Inverse Kinematics Problem from homogeneous transform matrix using a Newton-Raphson technique.

Parameters:
Tobj - homogeneous transform matrix
Returns:
joints position

invKine

RVector invKine(RMatrix4d Tobj,
                int mj,
                int endlink)
Computes the solution of the Inverse Kinematics Problem from homogeneous transform matrix using a Newton-Raphson or Taylor expansion techniques.

Parameters:
Tobj - homogeneous transform matrix
mj - value 0,1 to choose the technique: Newton-Raphson, Taylor expansion respectively.
endlink - the link to pretend is the end effector.
Returns:
joints position if converge otherwise null value.

jacobian

Matrix jacobian()
Computes the Jacobian matrix expressed in the base frame.

Returns:
jacobian matrix

jacobian

Matrix jacobian(int ref)
Computes the Jacobian matrix expressed in the ref-th frame.

Parameters:
ref - frame reference
Returns:
jacobian matrix

jacobianDot

Matrix jacobianDot()
Computes the Jacobian time derivative matrix expressed in the base frame.

Returns:
jacobian time derivative matrix

jacobianDot

Matrix jacobianDot(int ref)
Computes the Jacobian time derivative matrix expressed in the ref-th frame.

Parameters:
ref - frame reference
Returns:
jacobian time derivative matrix

jacobianDLSinv

Matrix jacobianDLSinv(double eps,
                      double lambdaMax)
Computes the 6x6 inverse Jacobian matrix based on the Damped Least-Squares scheme.

Parameters:
eps - the area of singular region
lambdaMax - the maximum damping factor
Returns:
inverse jacobian matrix

kine

RMatrix4d kine()
Computes the solution of the Forward Kinematics Problem.

Returns:
homogeneous transform matrix

kine

RMatrix4d kine(int j)
Computes the solution of the Forward Kinematics Problem for the link j.

Parameters:
j - link of forward kinematic
Returns:
homogeneous transform matrix

dTdqi

RMatrix4d dTdqi(int j)
Computes the partial derivative of homogeneous transform respect j-th joint.

Parameters:
j - joint
Returns:
homogeneous partial derivative transform

acceleration

RVector acceleration(RVector q,
                     RVector qp,
                     RVector tau)
Computes the solution of the Forward Dynamics Problem.

Parameters:
q - the vector joints position
qp - the vector joints velocity
tau - the vector joints torque
Returns:
the vector joints acceleration

acceleration

RVector acceleration(double[] q,
                     double[] qp,
                     double[] tau)
Computes the solution of the Forward Dynamics Problem.

Parameters:
q - array of joints position
qp - array of joints velocity
tau - array of joints torque
Returns:
the array of joints acceleration

acceleration

RVector acceleration(RVector q,
                     RVector qp,
                     RVector tauCmd,
                     RVector3d Fext,
                     RVector3d Next)
Computes the solution of the Forward Dynamics Problem with load applied to the last link.

Parameters:
q - joints position
qp - joints velocity
tauCmd - joints torque
Fext - load applied at last link
Next - load applied at last link
Returns:
joints acceleration

acceleration

RVector acceleration(double[] q,
                     double[] qp,
                     double[] tauCmd,
                     double[] Fext,
                     double[] Next)
Computes the solution of the Forward Dynamics Problem with load applied to the last link.

Parameters:
q - the array of joints position
qp - the array of joints velocity
tauCmd - the array of joints torque
Fext - the array of the load applied at last link
Next - the array of the load applied at last link
Returns:
the array of joints acceleration

torque

RVector torque(RVector q,
               RVector qp,
               RVector qpp)
Computes the solution of the Inverse Dynamics Problem.

Parameters:
q - joints position
qp - joints velocity
qpp - joints acceleration
Returns:
joints torque

torque

RVector torque(double[] q,
               double[] qp,
               double[] qpp)
Computes the solution of the Inverse Dynamics Problem.

Parameters:
q - the array of joints position
qp - the array of joints velocity
qpp - the array of joints acceleration
Returns:
the array of joints torque

torque

RVector torque(RVector q,
               RVector qp,
               RVector qpp,
               RVector3d Fext,
               RVector3d Next)
Computes the solution of the Inverse Dynamics Problem with load applied to the last link.

Parameters:
q - joints position
qp - joints velocity
qpp - joints acceleration
Fext - load applied at last link
Next - load applied at last link
Returns:
joints torque

torque

RVector torque(double[] q,
               double[] qp,
               double[] qpp,
               double[] Fext,
               double[] Next)
Computes the solution of the Inverse Dynamics Problem with load applied to the last link.

Parameters:
q - the array of joints position
qp - the array of joints velocity
qpp - the array of joints acceleration
Fext - the array of the load applied at last link
Next - the array of the load applied at last link
Returns:
the array of joints torque

torqueGravity

RVector torqueGravity()
Computes the torques from the gravity effect.

Returns:
joints torque

torqueC

RVector torqueC(RVector qp)
Computes the torques from the Coriolis and centrifugal effect.

Parameters:
qp - joints velocity
Returns:
joints torque

torqueViscousFriction

RVector torqueViscousFriction(RVector qp)
Computes the torques from the viscous friction.

Parameters:
qp - joints velocity
Returns:
joints torque

torqueCoulombFriction

RVector torqueCoulombFriction(RVector qp)
Computes the torques from the Coulomb friction.

Parameters:
qp - joints velocity
Returns:
joints torque

inertia

Matrix inertia(RVector q)
Computes the inertia matrix.

Call C++ Robot method

 inertia(const ColumnVector &q)
 

Parameters:
q - joints position
Returns:
intertia matrix

getGravity

RVector3d getGravity()
Gets gravity vector.

Returns:
the gravity vector

setGravity

void setGravity(RVector3d g)
Sets the gravity vector.

Parameters:
g - the new gravity vector.