|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |
public interface Robot
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.
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 |
---|
static final boolean DEBUG
static final int INITROBOT_DIM
static final int INITMOTOR_DIM
static final int JACOBIAN_DIMENSION
static final int HOMOGENEOUS_MATRIX_DIM
static final int SPACE_DIM
Method Detail |
---|
short getID()
XmlRobot getRobotConfiguration()
int getDof()
int getAvailableDof()
RVector getQMax()
RVector getQMin()
RVector getQOffset()
RVector getQ()
double getQ(int i)
i
- joint
RVector getQp()
RVector getQpp()
void setQ(RVector q)
q
- vector of joints positionvoid setQ(double[] q)
q
- vector of joints positionvoid setQ(double q, int i)
q
- joint positioni
- jointvoid setQp(RVector qp)
qp
- vector of joints velocityvoid setQp(double[] qp)
qp
- array of joints velocityvoid setQpp(RVector qpp)
qpp
- vector of joints positionvoid setQpp(double[] qpp)
qpp
- the array of joints positionRVector invKine(RMatrix4d Tobj)
Tobj
- homogeneous transform matrix
RVector invKine(RMatrix4d Tobj, int mj, int endlink)
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.
Matrix jacobian()
Matrix jacobian(int ref)
ref
- frame reference
Matrix jacobianDot()
Matrix jacobianDot(int ref)
ref
- frame reference
Matrix jacobianDLSinv(double eps, double lambdaMax)
eps
- the area of singular regionlambdaMax
- the maximum damping factor
RMatrix4d kine()
RMatrix4d kine(int j)
j
- link of forward kinematic
RMatrix4d dTdqi(int j)
j
- joint
RVector acceleration(RVector q, RVector qp, RVector tau)
q
- the vector joints positionqp
- the vector joints velocitytau
- the vector joints torque
RVector acceleration(double[] q, double[] qp, double[] tau)
q
- array of joints positionqp
- array of joints velocitytau
- array of joints torque
RVector acceleration(RVector q, RVector qp, RVector tauCmd, RVector3d Fext, RVector3d Next)
q
- joints positionqp
- joints velocitytauCmd
- joints torqueFext
- load applied at last linkNext
- load applied at last link
RVector acceleration(double[] q, double[] qp, double[] tauCmd, double[] Fext, double[] Next)
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
RVector torque(RVector q, RVector qp, RVector qpp)
q
- joints positionqp
- joints velocityqpp
- joints acceleration
RVector torque(double[] q, double[] qp, double[] qpp)
q
- the array of joints positionqp
- the array of joints velocityqpp
- the array of joints acceleration
RVector torque(RVector q, RVector qp, RVector qpp, RVector3d Fext, RVector3d Next)
q
- joints positionqp
- joints velocityqpp
- joints accelerationFext
- load applied at last linkNext
- load applied at last link
RVector torque(double[] q, double[] qp, double[] qpp, double[] Fext, double[] Next)
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
RVector torqueGravity()
RVector torqueC(RVector qp)
qp
- joints velocity
RVector torqueViscousFriction(RVector qp)
qp
- joints velocity
RVector torqueCoulombFriction(RVector qp)
qp
- joints velocity
Matrix inertia(RVector q)
Call C++ Robot method
inertia(const ColumnVector &q)
q
- joints position
RVector3d getGravity()
void setGravity(RVector3d g)
g
- the new gravity vector.
|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |