|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |
java.lang.Object javax.robotics.engine.JRoboOp javax.robotics.engine.robots.DHRobot javax.robotics.engine.robots.DHRobot3D
public class DHRobot3D
This class implements graphic 3D, kinematics and dynamics model of a robot manipulator based on Denavit-Hartenberg table.
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 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 |
---|
public DHRobot3D(int nLinks, double[] initRobot)
nLinks
- number of robot linksinitRobot
- vector of robot parameter; dimension: nLinks x 23DHRobot.DHRobot(int, double[])
public DHRobot3D(int nLinks, double[] initRobot, double[] initMotor)
nLinks
- number of links or robotinitRobot
- vector of robot parameter; dimension: nLinks x 19initMotor
- vector of motor robot parameter; dimension: nLinks x 4DHRobot.DHRobot(int, double[], double[])
public DHRobot3D(java.net.URI uri) throws org.apache.xmlbeans.XmlException, java.io.IOException
uri
- xml configuration file URI of robot parameter
org.apache.xmlbeans.XmlException
java.io.IOException
public DHRobot3D(java.lang.String fileName) throws org.apache.xmlbeans.XmlException, java.io.IOException
fileName
- xml configuration file name of robot parameter
org.apache.xmlbeans.XmlException
java.io.IOException
public DHRobot3D(java.io.File fileName) throws org.apache.xmlbeans.XmlException, java.io.IOException
fileName
- xml configuration file name of robot parameter
org.apache.xmlbeans.XmlException
java.io.IOException
public DHRobot3D(java.io.InputStream fileName) throws org.apache.xmlbeans.XmlException, java.io.IOException
fileName
- xml configuration file name of robot parameter
org.apache.xmlbeans.XmlException
java.io.IOException
Method Detail |
---|
public final boolean isJointPrismatic(int i)
Robot3D
isJointPrismatic
in interface Robot3D
i
- the joint
public boolean isJointImmobile(int i)
Robot3D
isJointImmobile
in interface Robot3D
i
- the joint
public final javax.media.j3d.BranchGroup getModel3D()
Robot3D
getModel3D
in interface Robot3D
public final void setQ3DOnly(RVector q)
Robot3D
setQ3DOnly
in interface Robot3D
q
- the new positions.public final void setQ3DOnly(double[] q)
Robot3D
setQ3DOnly
in interface Robot3D
q
- the new positions.public final void setQ3DOnly(double q, int i)
Robot3D
setQ3DOnly
in interface Robot3D
q
- the new position.i
- the joint.public final void setQ3D(RVector q)
Robot3D
setQ3D
in interface Robot3D
q
- the new positions.public final void setQ3D(double[] q)
Robot3D
setQ3D
in interface Robot3D
q
- the new positions.public final void setQ3D(double q, int i)
Robot3D
setQ3D
in interface Robot3D
q
- the new position.i
- the joint.public RMatrix4d getTransformMatrix(int i)
getTransformMatrix
in interface Robot3D
i
- the i-th joint;
|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |