|
|||||||||
| PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
| SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD | ||||||||
java.lang.Objectjavax.robotics.engine.JRoboOp
javax.robotics.engine.controllers.GravityCompensation
public class GravityCompensation
This class implements position controller with gravity compensation.
The scheme of the control:
| Field Summary |
|---|
| Fields inherited from class javax.robotics.engine.JRoboOp |
|---|
ID, Version |
| Constructor Summary | |
|---|---|
GravityCompensation(Robot robot,
double Kdp,
double Kpp)
Gravity compensation controller class constructor with positional jacobian. |
|
GravityCompensation(Robot robot,
double Kdp,
double Kpp,
double Kdo,
double Kpo)
Gravity compensation 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[] pd,
double[] quatd)
Sets the output torque for a desired end effector position and angular position. |
RVector |
torqueCmd(RVector pd)
Sets the output torque for a desired end effector position. |
RVector |
torqueCmd(RVector3d pd)
Sets the output torque for a desired end effector position. |
RVector |
torqueCmd(RVector3d pd,
Quaternion quatd)
Sets the output torque for a desired end effector position and angular position. |
RVector |
torqueCmd(RVector3d pdpp,
RVector3d pdp,
RVector3d pd)
Sets the output torque for a desired end effector position. |
RVector |
torqueCmd(RVector3d pdpp,
RVector3d pdp,
RVector3d pd,
RVector3d wdp,
RVector3d wd,
Quaternion quatd)
Sets the output torque for a desired end effector position and angular position. |
| Methods inherited from class java.lang.Object |
|---|
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait |
| Constructor Detail |
|---|
public GravityCompensation(Robot robot,
double Kdp,
double Kpp,
double Kdo,
double Kpo)
robot - Robot class.Kdp - end effector velocity gainKpp - end effector position error gainKdo - end effector orientation angular rate gainKpo - end effector orientation error gain
public GravityCompensation(Robot robot,
double Kdp,
double Kpp)
robot - Robot class.Kdp - end effector velocity gainKpp - end effector position error gain| Method Detail |
|---|
public final short getID()
getID in interface ControllergetID in class JRoboOppublic final short getRobotID()
Controller
getRobotID in interface Controllerpublic RVector3d getPositionError()
EndEffController
getPositionError in interface EndEffControllerpublic RVector3d getOrientationError()
EndEffControllerη(q)&epsilond - &etad&epsilon(q) - S(&epsilond)&epsilon(q)
where η and ε are the vector and the scalar components of quaternion respectively.
getOrientationError in interface EndEffController
public double[] torqueCmd(double[] pd,
double[] quatd)
pd - desired positionquatd - desired vector angular position: quaternion (s,v1,v2,v3)
public RVector torqueCmd(RVector3d pd,
Quaternion quatd)
pd - desired positionquatd - desired vector angular position: quaternion (s,v1,v2,v3)
public RVector torqueCmd(RVector3d pd)
pd - desired position
public RVector torqueCmd(RVector pd)
pd - desired position
public RVector torqueCmd(RVector3d pdpp,
RVector3d pdp,
RVector3d pd,
RVector3d wdp,
RVector3d wd,
Quaternion quatd)
torqueCmd in interface EndEffControllerpdpp - null vectorpdp - null vectorpd - desired positionwdp - null vectorquatd - desired vector angular position: quaternion (s,v1,v2,v3)wd - desired angular velocity
public RVector torqueCmd(RVector3d pdpp,
RVector3d pdp,
RVector3d pd)
torqueCmd in interface EndEffControllerpdpp - null vectorpdp - null vectorpd - desired position
|
|||||||||
| PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
| SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD | ||||||||