javax.robotics.engine.robots
Class DHRobot

java.lang.Object
  extended by javax.robotics.engine.JRoboOp
      extended by javax.robotics.engine.robots.DHRobot
All Implemented Interfaces:
java.io.Serializable, Robot
Direct Known Subclasses:
DHRobot3D

public class DHRobot
extends JRoboOp
implements Robot

This class implements kinematics and dynamics model of a robot manipulator based on Denavit-Hartenberg table.

Wrapper class for C++ library ROBOOP.

Since:
1.0.0
Version:
30/10/2005
Author:
Carmine Lia
See Also:
Serialized Form

Field Summary
 
Fields inherited from class javax.robotics.engine.JRoboOp
ID, Version
 
Fields inherited from interface javax.robotics.engine.robots.Robot
DEBUG, HOMOGENEOUS_MATRIX_DIM, INITMOTOR_DIM, INITROBOT_DIM, JACOBIAN_DIMENSION, SPACE_DIM
 
Constructor Summary
DHRobot()
          Default Robot constructor.
DHRobot(java.io.File fileName)
          Robot constructor with file parameter.
DHRobot(java.io.InputStream fileName)
          Robot constructor with xml file parameter as input stream.
DHRobot(int nLinks, double[] initRobot)
          Robot constructor with init parameter.
DHRobot(int nLinks, double[] initRobot, double[] initMotor)
          Robot constructor with init parameter and motor parameter.
DHRobot(java.lang.String fileName)
          Robot constructor with xml file parameter.
DHRobot(java.lang.String fileName, java.lang.String robotName)
          Deprecated.  
DHRobot(java.net.URI uri)
          Robot constructor with URI of xml file parameter.
 
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.
 
Methods inherited from class javax.robotics.engine.JRoboOp
acceleration, acceleration, createComputedTorqueMethod, createGravityCompensation, createImpedance, createPDGravityComp, createProportionalDerivative, createResolveRateAcceleration, createRobot, createRobot, createRobot, createRobot, createRobustControl, createSplinePath, createSplineQuaternion, dTdqi, getAvDof, getConverge, getDof, getError, getGravity, getPosErrorGCOMP, getPosErrorRRA, getQ, getQ, getQMax, getQMin, getQOffset, getQp, getQpp, getQuatErrorGCOMP, getQuatErrorRRA, impedanceControl, inertia, interpolate, interpolatePathQuat, interpolateQuat, invKine, invKine, jacobian, jacobian, jacobianDLSinv, jacobianDot, jacobianDot, kine, kine, setGravity, setKdCTM, setKdPD, setKdPDG, setKdRC, setKpCTM, setKpPD, setKpPDG, setKpRC, setQ, setQ, setQp, setQpp, torque, torque, torqueCmdCTM, torqueCmdGCOMP, torqueCmdGCOMP, torqueCmdPD, torqueCmdPDG, torqueCmdRC, torqueCmdRRA, torqueCmdRRA, torqueCoriolis, torqueCoulombFriction, torqueGravity, torqueViscousFriction
 
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
 

Constructor Detail

DHRobot

public DHRobot()
Default Robot constructor.


DHRobot

public DHRobot(int nLinks,
               double[] initRobot)
Robot constructor with init parameter.

Column Variable Description
1 σ joint type (revolute=0, prismatic=1)
2 θ Denavit-Hartenberg parameter
3 d Denavit-Hartenberg parameter
4 a Denavit-Hartenberg parameter
5 α Denavit-Hartenberg parameter
6 qmin minimum value of joint variable
7 qmax maximum value of joint variable
8 θoff joint offset
9 m mass of the link
10 cx center of mass along axis x
11 cy center of mass along axis y
12 cz center of mass along axis z
13 Ixx element xx of the inertia tensor matrix
14 Ixy element xy of the inertia tensor matrix
15 Ixz element xz of the inertia tensor matrix
16 Iyy element yy of the inertia tensor matrix
17 Iyz element yz of the inertia tensor matrix
18 Izz element zz of the inertia tensor matrix
19 Im motor rotor inertia
20 Gr motor gear ratio
21 B motor viscous friction coefficient
22 Cf motor Coulomb friction coefficient
23 immobile flag for the kinematics and inverse kinematics (if true joint is locked, if false joint is free)

Parameters:
nLinks - number of robot links
initRobot - vector of robot parameter; dimension: nLinks x 23

DHRobot

public DHRobot(int nLinks,
               double[] initRobot,
               double[] initMotor)
Robot constructor with init parameter and motor parameter.

Parameters:
nLinks - number of links or robot
initRobot - vector of robot parameter; dimension: nLinks x 19
initMotor - vector of motor robot parameter; dimension: nLinks x 4
See Also:
DHRobot(int, double[])

DHRobot

public DHRobot(java.lang.String fileName,
               java.lang.String robotName)
Deprecated. 

Robot constructor with ROBOOP file parameter.

Parameters:
fileName - configuration file name of robot parameter
robotName - name of the robot

DHRobot

public DHRobot(java.net.URI uri)
        throws org.apache.xmlbeans.XmlException,
               java.io.IOException
Robot constructor with URI of xml file parameter. The URI can be an URL or a file path.

Parameters:
uri - xml configuration file URI of robot parameter
Throws:
org.apache.xmlbeans.XmlException
java.io.IOException

DHRobot

public DHRobot(java.lang.String fileName)
        throws org.apache.xmlbeans.XmlException,
               java.io.IOException
Robot constructor with xml file parameter.

Parameters:
fileName - xml configuration file name of robot parameter
Throws:
org.apache.xmlbeans.XmlException
java.io.IOException

DHRobot

public DHRobot(java.io.File fileName)
        throws org.apache.xmlbeans.XmlException,
               java.io.IOException
Robot constructor with file parameter.

Parameters:
fileName - xml configuration file name of robot parameter
Throws:
org.apache.xmlbeans.XmlException
java.io.IOException

DHRobot

public DHRobot(java.io.InputStream fileName)
        throws org.apache.xmlbeans.XmlException,
               java.io.IOException
Robot constructor with xml file parameter as input stream.

Parameters:
fileName - xml configuration file name of robot parameter
Throws:
org.apache.xmlbeans.XmlException
java.io.IOException
Method Detail

getID

public final short getID()
Gets Robot class ID

Specified by:
getID in interface Robot
Specified by:
getID in class JRoboOp
Returns:
ID

getRobotConfiguration

public final XmlRobot getRobotConfiguration()
Description copied from interface: Robot
Gets the robot configuration.

Specified by:
getRobotConfiguration in interface Robot
Returns:
the robot configuration.

getDof

public final int getDof()
Description copied from interface: Robot
Gets the degrees of freedom of robot.

Specified by:
getDof in interface Robot
Returns:
degrees of freedom of robot manipulator

getAvailableDof

public final int getAvailableDof()
Description copied from interface: Robot
Gets the available degrees of freedom of robot.

Specified by:
getAvailableDof in interface Robot
Returns:
the available degrees of freedom of robot manipulator

getQMin

public final RVector getQMin()
Description copied from interface: Robot
Gets joints minimum position.

Specified by:
getQMin in interface Robot
Returns:
vector of joints minimum position.

getQMax

public final RVector getQMax()
Description copied from interface: Robot
Gets joints maximum position.

Specified by:
getQMax in interface Robot
Returns:
vector of joints maximum position.

getQOffset

public final RVector getQOffset()
Description copied from interface: Robot
Gets joints offset position.

Specified by:
getQOffset in interface Robot
Returns:
vector of joints offset position.

getQ

public RVector getQ()
Description copied from interface: Robot
Gets joints position. The position is computed subtracting the offset.

Specified by:
getQ in interface Robot
Returns:
vector of joints position.

getQ

public double getQ(int i)
Description copied from interface: Robot
Position of i-th joint. The position is computed subtracting the offset.

Specified by:
getQ in interface Robot
Parameters:
i - joint
Returns:
joint position.

getQp

public RVector getQp()
Description copied from interface: Robot
Gets joints velocity.

Specified by:
getQp in interface Robot
Returns:
vector of joints velocity

getQpp

public RVector getQpp()
Description copied from interface: Robot
Gets joints acceleration.

Specified by:
getQpp in interface Robot
Returns:
vector of joints acceleration

setQ

public void setQ(RVector q)
Description copied from interface: Robot
Sets joints position. The position is computed adding the offset.

Specified by:
setQ in interface Robot
Parameters:
q - vector of joints position

setQ

public void setQ(double[] q)
Description copied from interface: Robot
Sets joints position. The position is computed adding the offset.

Specified by:
setQ in interface Robot
Parameters:
q - vector of joints position

setQ

public void setQ(double q,
                 int i)
Description copied from interface: Robot
Sets the position pf i-th joint position. The position is computed adding the offset.

Specified by:
setQ in interface Robot
Parameters:
q - joint position
i - joint

setQp

public void setQp(RVector qp)
Description copied from interface: Robot
Sets joints velocity.

Specified by:
setQp in interface Robot
Parameters:
qp - vector of joints velocity

setQp

public void setQp(double[] qp)
Description copied from interface: Robot
Sets joints velocity.

Specified by:
setQp in interface Robot
Parameters:
qp - array of joints velocity

setQpp

public void setQpp(RVector qpp)
Description copied from interface: Robot
Sets joints acceleration.

Specified by:
setQpp in interface Robot
Parameters:
qpp - vector of joints position

setQpp

public void setQpp(double[] qpp)
Description copied from interface: Robot
Sets joints acceleration.

Specified by:
setQpp in interface Robot
Parameters:
qpp - the array of joints position

invKine

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

Specified by:
invKine in interface Robot
Parameters:
Tobj - homogeneous transform matrix
Returns:
joints position

invKine

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

Specified by:
invKine in interface Robot
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

public Matrix jacobian()
Description copied from interface: Robot
Computes the Jacobian matrix expressed in the base frame.

Specified by:
jacobian in interface Robot
Returns:
jacobian matrix

jacobian

public Matrix jacobian(int ref)
Description copied from interface: Robot
Computes the Jacobian matrix expressed in the ref-th frame.

Specified by:
jacobian in interface Robot
Parameters:
ref - frame reference
Returns:
jacobian matrix

jacobianDot

public Matrix jacobianDot()
Description copied from interface: Robot
Computes the Jacobian time derivative matrix expressed in the base frame.

Specified by:
jacobianDot in interface Robot
Returns:
jacobian time derivative matrix

jacobianDot

public Matrix jacobianDot(int ref)
Description copied from interface: Robot
Computes the Jacobian time derivative matrix expressed in the ref-th frame.

Specified by:
jacobianDot in interface Robot
Parameters:
ref - frame reference
Returns:
jacobian time derivative matrix

jacobianDLSinv

public Matrix jacobianDLSinv(double eps,
                             double lambdaMax)
Description copied from interface: Robot
Computes the 6x6 inverse Jacobian matrix based on the Damped Least-Squares scheme.

Specified by:
jacobianDLSinv in interface Robot
Parameters:
eps - the area of singular region
lambdaMax - the maximum damping factor
Returns:
inverse jacobian matrix

kine

public RMatrix4d kine()
Description copied from interface: Robot
Computes the solution of the Forward Kinematics Problem.

Specified by:
kine in interface Robot
Returns:
homogeneous transform matrix

kine

public RMatrix4d kine(int j)
Description copied from interface: Robot
Computes the solution of the Forward Kinematics Problem for the link j.

Specified by:
kine in interface Robot
Parameters:
j - link of forward kinematic
Returns:
homogeneous transform matrix

dTdqi

public RMatrix4d dTdqi(int j)
Description copied from interface: Robot
Computes the partial derivative of homogeneous transform respect j-th joint.

Specified by:
dTdqi in interface Robot
Parameters:
j - joint
Returns:
homogeneous partial derivative transform

acceleration

public RVector acceleration(RVector q,
                            RVector qp,
                            RVector tau)
Description copied from interface: Robot
Computes the solution of the Forward Dynamics Problem.

Specified by:
acceleration in interface Robot
Parameters:
q - the vector joints position
qp - the vector joints velocity
tau - the vector joints torque
Returns:
the vector joints acceleration

acceleration

public RVector acceleration(double[] q,
                            double[] qp,
                            double[] tau)
Description copied from interface: Robot
Computes the solution of the Forward Dynamics Problem.

Specified by:
acceleration in interface Robot
Parameters:
q - array of joints position
qp - array of joints velocity
tau - array of joints torque
Returns:
the array of joints acceleration

acceleration

public RVector acceleration(RVector q,
                            RVector qp,
                            RVector tauCmd,
                            RVector3d Fext,
                            RVector3d Next)
Description copied from interface: Robot
Computes the solution of the Forward Dynamics Problem with load applied to the last link.

Specified by:
acceleration in interface Robot
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

public RVector acceleration(double[] q,
                            double[] qp,
                            double[] tauCmd,
                            double[] Fext,
                            double[] Next)
Description copied from interface: Robot
Computes the solution of the Forward Dynamics Problem with load applied to the last link.

Specified by:
acceleration in interface Robot
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

public RVector torque(RVector q,
                      RVector qp,
                      RVector qpp)
Description copied from interface: Robot
Computes the solution of the Inverse Dynamics Problem.

Specified by:
torque in interface Robot
Parameters:
q - joints position
qp - joints velocity
qpp - joints acceleration
Returns:
joints torque

torque

public RVector torque(double[] q,
                      double[] qp,
                      double[] qpp)
Description copied from interface: Robot
Computes the solution of the Inverse Dynamics Problem.

Specified by:
torque in interface Robot
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

public RVector torque(RVector q,
                      RVector qp,
                      RVector qpp,
                      RVector3d Fext,
                      RVector3d Next)
Description copied from interface: Robot
Computes the solution of the Inverse Dynamics Problem with load applied to the last link.

Specified by:
torque in interface Robot
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

public RVector torque(double[] q,
                      double[] qp,
                      double[] qpp,
                      double[] Fext,
                      double[] Next)
Description copied from interface: Robot
Computes the solution of the Inverse Dynamics Problem with load applied to the last link.

Specified by:
torque in interface Robot
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

public RVector torqueGravity()
Description copied from interface: Robot
Computes the torques from the gravity effect.

Specified by:
torqueGravity in interface Robot
Returns:
joints torque

torqueC

public RVector torqueC(RVector qp)
Description copied from interface: Robot
Computes the torques from the Coriolis and centrifugal effect.

Specified by:
torqueC in interface Robot
Parameters:
qp - joints velocity
Returns:
joints torque

torqueViscousFriction

public RVector torqueViscousFriction(RVector qp)
Description copied from interface: Robot
Computes the torques from the viscous friction.

Specified by:
torqueViscousFriction in interface Robot
Parameters:
qp - joints velocity
Returns:
joints torque

torqueCoulombFriction

public RVector torqueCoulombFriction(RVector qp)
Description copied from interface: Robot
Computes the torques from the Coulomb friction.

Specified by:
torqueCoulombFriction in interface Robot
Parameters:
qp - joints velocity
Returns:
joints torque

inertia

public Matrix inertia(RVector q)
Description copied from interface: Robot
Computes the inertia matrix.

Call C++ Robot method

 inertia(const ColumnVector &q)
 

Specified by:
inertia in interface Robot
Parameters:
q - joints position
Returns:
intertia matrix

getGravity

public RVector3d getGravity()
Description copied from interface: Robot
Gets gravity vector.

Specified by:
getGravity in interface Robot
Returns:
the gravity vector

setGravity

public void setGravity(RVector3d g)
Description copied from interface: Robot
Sets the gravity vector.

Specified by:
setGravity in interface Robot
Parameters:
g - the new gravity vector.