|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |
public interface EndEffController
Interface for different schemes of robot end effector position and orientation controller.
Method Summary | |
---|---|
RVector3d |
getOrientationError()
Gets the current orientation error. |
RVector3d |
getPositionError()
Gets the position error. |
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 interface javax.robotics.engine.controllers.Controller |
---|
getID, getRobotID |
Method Detail |
---|
RVector3d getPositionError()
RVector3d getOrientationError()
η(q)&epsilond - &etad&epsilon(q) - S(&epsilond)&epsilon(q)
where η and ε are the vector and the scalar components of quaternion respectively.
RVector torqueCmd(RVector3d pdpp, RVector3d pdp, RVector3d pd, RVector3d wdp, RVector3d wd, Quaternion quatd)
pdpp
- desired accelerationpdp
- desired velocitypd
- desired positionwdp
- desired angular accelerationwd
- desired angular velocityquatd
- desired vector angular position: quaternion (s,v1,v2,v3)
RVector torqueCmd(RVector3d pdpp, RVector3d pdp, RVector3d pd)
pdpp
- desired accelerationpdp
- desired velocitypd
- desired position
|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |