javax.robotics.engine.robots
Class DHRobot3D

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

public class DHRobot3D
extends DHRobot
implements Robot3D

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

Since:
1.0.3
Version:
11/11/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.Robot3D
PRISMATIC, REVOLUTE
 
Fields inherited from interface javax.robotics.engine.robots.Robot
DEBUG, HOMOGENEOUS_MATRIX_DIM, INITMOTOR_DIM, INITROBOT_DIM, JACOBIAN_DIMENSION, SPACE_DIM
 
Constructor Summary
DHRobot3D(java.io.File fileName)
          Robot constructor with xml file parameter.
DHRobot3D(java.io.InputStream fileName)
          Robot constructor with xml file parameter as input stream.
DHRobot3D(int nLinks, double[] initRobot)
          Robot constructor with init parameter.
DHRobot3D(int nLinks, double[] initRobot, double[] initMotor)
          Robot constructor with init parameter and motor parameter.
DHRobot3D(java.lang.String fileName)
          Robot constructor with xml file parameter.
DHRobot3D(java.net.URI uri)
          Robot constructor with URI of xml file parameter.
 
Method Summary
 javax.media.j3d.BranchGroup getModel3D()
          Gets the model 3D of robot manipulator.
 RMatrix4d getTransformMatrix(int i)
          Gets the 4x4 transformation matrix of i-th joint.
 boolean isJointImmobile(int i)
          Gets the immobile flag.
 boolean isJointPrismatic(int i)
          Gets the type of joint REVOLUTE or PRISMATIC
 void setQ3D(double[] q)
          Sets the position of the joints.
 void setQ3D(double q, int i)
          Sets the position of the i-th joint.
 void setQ3D(RVector q)
          Sets the position of the joints.
 void setQ3DOnly(double[] q)
          Sets the position of the joints only of 3D model.
 void setQ3DOnly(double q, int i)
          Sets the position of the i-th joint only of 3D model.
 void setQ3DOnly(RVector q)
          Sets the position of the joints only of 3D model.
 
Methods inherited from class javax.robotics.engine.robots.DHRobot
acceleration, acceleration, acceleration, acceleration, dTdqi, getAvailableDof, getDof, getGravity, getID, getQ, getQ, getQMax, getQMin, getQOffset, getQp, getQpp, getRobotConfiguration, inertia, invKine, invKine, jacobian, jacobian, jacobianDLSinv, jacobianDot, jacobianDot, kine, kine, setGravity, setQ, setQ, setQ, setQp, setQp, setQpp, setQpp, torque, torque, torque, torque, torqueC, torqueCoulombFriction, torqueGravity, torqueViscousFriction
 
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
 
Methods inherited from interface javax.robotics.engine.robots.Robot
acceleration, acceleration, acceleration, acceleration, dTdqi, getAvailableDof, getDof, getGravity, getID, getQ, getQ, getQMax, getQMin, getQOffset, getQp, getQpp, getRobotConfiguration, inertia, invKine, invKine, jacobian, jacobian, jacobianDLSinv, jacobianDot, jacobianDot, kine, kine, setGravity, setQ, setQ, setQ, setQp, setQp, setQpp, setQpp, torque, torque, torque, torque, torqueC, torqueCoulombFriction, torqueGravity, torqueViscousFriction
 

Constructor Detail

DHRobot3D

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

Parameters:
nLinks - number of robot links
initRobot - vector of robot parameter; dimension: nLinks x 23
See Also:
DHRobot.DHRobot(int, double[])

DHRobot3D

public DHRobot3D(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.DHRobot(int, double[], double[])

DHRobot3D

public DHRobot3D(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

DHRobot3D

public DHRobot3D(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

DHRobot3D

public DHRobot3D(java.io.File 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

DHRobot3D

public DHRobot3D(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

isJointPrismatic

public final boolean isJointPrismatic(int i)
Description copied from interface: Robot3D
Gets the type of joint REVOLUTE or PRISMATIC

Specified by:
isJointPrismatic in interface Robot3D
Parameters:
i - the joint
Returns:
true if prismatic false if revolute

isJointImmobile

public boolean isJointImmobile(int i)
Description copied from interface: Robot3D
Gets the immobile flag.

Specified by:
isJointImmobile in interface Robot3D
Parameters:
i - the joint
Returns:
the immobile flag.

getModel3D

public final javax.media.j3d.BranchGroup getModel3D()
Description copied from interface: Robot3D
Gets the model 3D of robot manipulator.

Specified by:
getModel3D in interface Robot3D
Returns:
the Java 3D model.

setQ3DOnly

public final void setQ3DOnly(RVector q)
Description copied from interface: Robot3D
Sets the position of the joints only of 3D model.

Specified by:
setQ3DOnly in interface Robot3D
Parameters:
q - the new positions.

setQ3DOnly

public final void setQ3DOnly(double[] q)
Description copied from interface: Robot3D
Sets the position of the joints only of 3D model.

Specified by:
setQ3DOnly in interface Robot3D
Parameters:
q - the new positions.

setQ3DOnly

public final void setQ3DOnly(double q,
                             int i)
Description copied from interface: Robot3D
Sets the position of the i-th joint only of 3D model.

Specified by:
setQ3DOnly in interface Robot3D
Parameters:
q - the new position.
i - the joint.

setQ3D

public final void setQ3D(RVector q)
Description copied from interface: Robot3D
Sets the position of the joints.

Specified by:
setQ3D in interface Robot3D
Parameters:
q - the new positions.

setQ3D

public final void setQ3D(double[] q)
Description copied from interface: Robot3D
Sets the position of the joints.

Specified by:
setQ3D in interface Robot3D
Parameters:
q - the new positions.

setQ3D

public final void setQ3D(double q,
                         int i)
Description copied from interface: Robot3D
Sets the position of the i-th joint.

Specified by:
setQ3D in interface Robot3D
Parameters:
q - the new position.
i - the joint.

getTransformMatrix

public RMatrix4d getTransformMatrix(int i)
Gets the 4x4 transformation matrix of i-th joint.

Specified by:
getTransformMatrix in interface Robot3D
Parameters:
i - the i-th joint;
Returns:
null (the homogeneous matrix.)