|
|||||||||
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
public class DHRobot
This class implements kinematics and dynamics model of a robot manipulator based on Denavit-Hartenberg table.
Wrapper class for C++ library ROBOOP.
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 java.lang.Object |
---|
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait |
Constructor Detail |
---|
public DHRobot()
public DHRobot(int nLinks, double[] initRobot)
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) |
nLinks
- number of robot linksinitRobot
- vector of robot parameter; dimension: nLinks x 23public DHRobot(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(int, double[])
public DHRobot(java.lang.String fileName, java.lang.String robotName)
fileName
- configuration file name of robot parameterrobotName
- name of the robotpublic DHRobot(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 DHRobot(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 DHRobot(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 DHRobot(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 short getID()
getID
in interface Robot
getID
in class JRoboOp
public final XmlRobot getRobotConfiguration()
Robot
getRobotConfiguration
in interface Robot
public final int getDof()
Robot
getDof
in interface Robot
public final int getAvailableDof()
Robot
getAvailableDof
in interface Robot
public final RVector getQMin()
Robot
getQMin
in interface Robot
public final RVector getQMax()
Robot
getQMax
in interface Robot
public final RVector getQOffset()
Robot
getQOffset
in interface Robot
public RVector getQ()
Robot
getQ
in interface Robot
public double getQ(int i)
Robot
getQ
in interface Robot
i
- joint
public RVector getQp()
Robot
getQp
in interface Robot
public RVector getQpp()
Robot
getQpp
in interface Robot
public void setQ(RVector q)
Robot
setQ
in interface Robot
q
- vector of joints positionpublic void setQ(double[] q)
Robot
setQ
in interface Robot
q
- vector of joints positionpublic void setQ(double q, int i)
Robot
setQ
in interface Robot
q
- joint positioni
- jointpublic void setQp(RVector qp)
Robot
setQp
in interface Robot
qp
- vector of joints velocitypublic void setQp(double[] qp)
Robot
setQp
in interface Robot
qp
- array of joints velocitypublic void setQpp(RVector qpp)
Robot
setQpp
in interface Robot
qpp
- vector of joints positionpublic void setQpp(double[] qpp)
Robot
setQpp
in interface Robot
qpp
- the array of joints positionpublic RVector invKine(RMatrix4d Tobj)
Robot
invKine
in interface Robot
Tobj
- homogeneous transform matrix
public RVector invKine(RMatrix4d Tobj, int mj, int endlink)
Robot
invKine
in interface Robot
Tobj
- homogeneous transform matrixmj
- value 0,1 to choose the technique: Newton-Raphson, Taylor
expansion respectively.endlink
- the link to pretend is the end effector.
public Matrix jacobian()
Robot
jacobian
in interface Robot
public Matrix jacobian(int ref)
Robot
jacobian
in interface Robot
ref
- frame reference
public Matrix jacobianDot()
Robot
jacobianDot
in interface Robot
public Matrix jacobianDot(int ref)
Robot
jacobianDot
in interface Robot
ref
- frame reference
public Matrix jacobianDLSinv(double eps, double lambdaMax)
Robot
jacobianDLSinv
in interface Robot
eps
- the area of singular regionlambdaMax
- the maximum damping factor
public RMatrix4d kine()
Robot
kine
in interface Robot
public RMatrix4d kine(int j)
Robot
kine
in interface Robot
j
- link of forward kinematic
public RMatrix4d dTdqi(int j)
Robot
dTdqi
in interface Robot
j
- joint
public RVector acceleration(RVector q, RVector qp, RVector tau)
Robot
acceleration
in interface Robot
q
- the vector joints positionqp
- the vector joints velocitytau
- the vector joints torque
public RVector acceleration(double[] q, double[] qp, double[] tau)
Robot
acceleration
in interface Robot
q
- array of joints positionqp
- array of joints velocitytau
- array of joints torque
public RVector acceleration(RVector q, RVector qp, RVector tauCmd, RVector3d Fext, RVector3d Next)
Robot
acceleration
in interface Robot
q
- joints positionqp
- joints velocitytauCmd
- joints torqueFext
- load applied at last linkNext
- load applied at last link
public RVector acceleration(double[] q, double[] qp, double[] tauCmd, double[] Fext, double[] Next)
Robot
acceleration
in interface Robot
q
- the array of joints positionqp
- the array of joints velocitytauCmd
- the array of joints torqueFext
- the array of the load applied at last linkNext
- the array of the load applied at last link
public RVector torque(RVector q, RVector qp, RVector qpp)
Robot
torque
in interface Robot
q
- joints positionqp
- joints velocityqpp
- joints acceleration
public RVector torque(double[] q, double[] qp, double[] qpp)
Robot
torque
in interface Robot
q
- the array of joints positionqp
- the array of joints velocityqpp
- the array of joints acceleration
public RVector torque(RVector q, RVector qp, RVector qpp, RVector3d Fext, RVector3d Next)
Robot
torque
in interface Robot
q
- joints positionqp
- joints velocityqpp
- joints accelerationFext
- load applied at last linkNext
- load applied at last link
public RVector torque(double[] q, double[] qp, double[] qpp, double[] Fext, double[] Next)
Robot
torque
in interface Robot
q
- the array of joints positionqp
- the array of joints velocityqpp
- the array of joints accelerationFext
- the array of the load applied at last linkNext
- the array of the load applied at last link
public RVector torqueGravity()
Robot
torqueGravity
in interface Robot
public RVector torqueC(RVector qp)
Robot
torqueC
in interface Robot
qp
- joints velocity
public RVector torqueViscousFriction(RVector qp)
Robot
torqueViscousFriction
in interface Robot
qp
- joints velocity
public RVector torqueCoulombFriction(RVector qp)
Robot
torqueCoulombFriction
in interface Robot
qp
- joints velocity
public Matrix inertia(RVector q)
Robot
Call C++ Robot method
inertia(const ColumnVector &q)
inertia
in interface Robot
q
- joints position
public RVector3d getGravity()
Robot
getGravity
in interface Robot
public void setGravity(RVector3d g)
Robot
setGravity
in interface Robot
g
- the new gravity vector.
|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |