|
|||||||||
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.controllers.ProportionalDerivative
public class ProportionalDerivative
This class implements Proportional Derivative joints position controller.
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.controllers.JointController |
---|
WRONG_SIZE |
Constructor Summary | |
---|---|
ProportionalDerivative(Robot robot,
DMatrix Kp,
DMatrix Kd)
Proportional Derivative joints position controller class constructor. |
|
ProportionalDerivative(Robot robot,
double[] Kp,
double[] Kd)
Proportional Derivative joints position controller class constructor. |
Method Summary | |
---|---|
short |
getID()
Gets Controller class ID. |
DMatrix |
getKd()
Gets the velocity error gain matrix. |
DMatrix |
getKp()
Gets the position error gain matrix. |
short |
getRobotID()
Gets Robot class ID linked to controller. |
short |
setKd(DMatrix Kd)
Sets the velocity error gain matrix. |
short |
setKd(double[] Kd)
Sets the velocity error gain matrix. |
short |
setKp(DMatrix Kp)
Sets the position error gain matrix. |
short |
setKp(double[] Kp)
Sets the position error gain matrix. |
double[] |
torqueCmd(double[]... qd)
Sets the output torque for a desired joint position and velocity. |
RVector |
torqueCmd(RVector... qd)
Sets the output torque for a desired joint position and velocity. |
Methods inherited from class java.lang.Object |
---|
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait |
Constructor Detail |
---|
public ProportionalDerivative(Robot robot, double[] Kp, double[] Kd)
robot
- Robot class.Kp
- diagonal matrix joint position error gain matrix.Kd
- diagonal matrix joint velocity error gain matrix.public ProportionalDerivative(Robot robot, DMatrix Kp, DMatrix Kd)
robot
- Robot class.Kp
- diagonal matrix joint position error gain matrix.Kd
- diagonal matrix joint velocity error gain matrix.Method Detail |
---|
public final short getID()
getID
in interface Controller
getID
in class JRoboOp
public final short getRobotID()
Controller
getRobotID
in interface Controller
public final DMatrix getKp()
JointController
getKp
in interface JointController
public final DMatrix getKd()
JointController
getKd
in interface JointController
public short setKp(double[] Kp)
Kp
- position error gain diagonal matrix
public short setKd(double[] Kd)
Kd
- velocity error gain diagonal matrix
public short setKp(DMatrix Kp)
JointController
Call C++ method
set_Kp(const DiagonalMatrixr &Kp)
setKp
in interface JointController
Kp
- position error gain diagonal matrix
public short setKd(DMatrix Kd)
JointController
Call C++ method
set_Kd(const DiagonalMatrixr &Kd)
setKd
in interface JointController
Kd
- velocity error gain diagonal matrix
public double[] torqueCmd(double[]... qd)
torqueCmd
in interface JointController
qd
- array of desired joint position and desired joint velocity.
public RVector torqueCmd(RVector... qd)
torqueCmd
in interface JointController
qd
- array of desired joint position and desired joint velocity.
|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |