javax.robotics.engine.controllers
Class ResolvedRateAcceleration

java.lang.Object
  extended by javax.robotics.engine.JRoboOp
      extended by javax.robotics.engine.controllers.ResolvedRateAcceleration
All Implemented Interfaces:
Controller, EndEffController

public class ResolvedRateAcceleration
extends JRoboOp
implements EndEffController

This class implements Resolved Rate Acceleration controller. The scheme of the control:
scheme of resolved rate acceleration
 control
the dynamics model of robot:  B(q)*q'' + n(q,q') = u, n(q,q') = C(q,q')*q'+ Fq'+ g(q)
the resultant error equation:  e'' + Kd*e' + Kp*e = 0

Wrapper class for C++ library ROBOOP.

Since:
1.0.0
Version:
7/10/2005
Author:
Carmine Lia

Field Summary
 
Fields inherited from class javax.robotics.engine.JRoboOp
ID, Version
 
Constructor Summary
ResolvedRateAcceleration(Robot robot, double Kdp, double Kpp)
          Resolved Rate Acceleration controller class constructor with positional jacobian.
ResolvedRateAcceleration(Robot robot, double Kdp, double Kpp, double Kdo, double Kpo)
          Resolved Rate Acceleration controller class constructor.
 
Method Summary
 short getID()
          Gets Controller class ID.
 RVector3d getOrientationError()
          Gets the current orientation error.
 RVector3d getPositionError()
          Gets the position error.
 short getRobotID()
          Gets Robot class ID linked to controller.
 double[] torqueCmd(double[] pdpp, double[] pdp, double[] pd, double[] wdp, double[] wd, double[] quatd)
          Sets the output torque for a desired end effector: acceleration, velocity, position, angular acceleration, angular velocity, angular position.
 RVector torqueCmd(RVector3d pdpp, RVector3d pdp, RVector3d pd)
          Sets the output torque for a desired end effector: acceleration, velocity, position.
 RVector torqueCmd(RVector3d pdpp, RVector3d pdp, RVector3d pd, RVector3d wdp, RVector3d wd, Quaternion quatd)
          Sets the output torque for a desired end effector: acceleration, velocity, position, angular acceleration, angular velocity, angular position.
 
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

ResolvedRateAcceleration

public ResolvedRateAcceleration(Robot robot,
                                double Kdp,
                                double Kpp,
                                double Kdo,
                                double Kpo)
Resolved Rate Acceleration controller class constructor.

Parameters:
robot - Robot class.
Kdp - end effector velocity error gain
Kpp - end effector position error gain
Kdo - end effector orientation angular rate gain
Kpo - end effector orientation error gain

ResolvedRateAcceleration

public ResolvedRateAcceleration(Robot robot,
                                double Kdp,
                                double Kpp)
Resolved Rate Acceleration controller class constructor with positional jacobian.

Parameters:
robot - Robot class.
Kdp - end effector velocity error gain
Kpp - end effector position error gain
Method Detail

getID

public final short getID()
Gets Controller class ID.

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

getRobotID

public final short getRobotID()
Description copied from interface: Controller
Gets Robot class ID linked to controller.

Specified by:
getRobotID in interface Controller
Returns:
ID

getPositionError

public RVector3d getPositionError()
Description copied from interface: EndEffController
Gets the position error.

Specified by:
getPositionError in interface EndEffController
Returns:
the position error vector.

getOrientationError

public RVector3d getOrientationError()
Description copied from interface: EndEffController
Gets the current orientation error. The error is computed form quaternion as:

η(q)&epsilond - &etad&epsilon(q) - S(&epsilond)&epsilon(q)

where η and ε are the vector and the scalar components of quaternion respectively.

Specified by:
getOrientationError in interface EndEffController
Returns:
the orientation error vector.

torqueCmd

public double[] torqueCmd(double[] pdpp,
                          double[] pdp,
                          double[] pd,
                          double[] wdp,
                          double[] wd,
                          double[] quatd)
Sets the output torque for a desired end effector: acceleration, velocity, position, angular acceleration, angular velocity, angular position.

Parameters:
pdpp - desired acceleration
pdp - desired velocity
pd - desired position
wdp - desired angular acceleration
wd - desired angular velocity
quatd - desired vector angular position: quaternion (s,v1,v2,v3)
Returns:
the output torque

torqueCmd

public RVector torqueCmd(RVector3d pdpp,
                         RVector3d pdp,
                         RVector3d pd,
                         RVector3d wdp,
                         RVector3d wd,
                         Quaternion quatd)
Sets the output torque for a desired end effector: acceleration, velocity, position, angular acceleration, angular velocity, angular position.

Specified by:
torqueCmd in interface EndEffController
Parameters:
pdpp - desired acceleration
pdp - desired velocity
pd - desired position
wdp - desired angular acceleration
wd - desired angular velocity
quatd - desired vector angular position: quaternion (s,v1,v2,v3)
Returns:
the output torque

torqueCmd

public RVector torqueCmd(RVector3d pdpp,
                         RVector3d pdp,
                         RVector3d pd)
Sets the output torque for a desired end effector: acceleration, velocity, position. Only the positional jacobian is used.

Specified by:
torqueCmd in interface EndEffController
Parameters:
pdpp - desired acceleration
pdp - desired velocity
pd - desired position
Returns:
the output torque