|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |
java.lang.Object javax.robotics.engine.clik.ClikJacobianInverse javax.robotics.engine.clik.ClikJacobianTranspose
public class ClikJacobianTranspose
Closed Loop Inverse Kinematics with Jacobian transpose. The class implements
this scheme:
The orientation error is computed as quaternion error.
The integration method used is the forward Euler.
Constructor Summary | |
---|---|
ClikJacobianTranspose(Robot robot,
DMatrix Kp,
DMatrix Ko)
Costructor with default sample time, dt = 1e-3. |
|
ClikJacobianTranspose(Robot robot,
DMatrix Kp,
DMatrix Ko,
double dt)
Costructor. |
Method Summary | |
---|---|
void |
step(RVector3d pd,
RVector3d ppd,
Quaternion quatd,
RVector3d wd)
Compute the joints position and velocity from a given desired end effector position and orientation. |
Methods inherited from class javax.robotics.engine.clik.ClikJacobianInverse |
---|
getEps, getJointsPosition, getJointsVelocity, getKo, getKp, getLambdaMax, getOrientationError, getPositionError, getSampleTime, setEps, setKo, setKp, setLambdaMax, setSampleTime |
Methods inherited from class java.lang.Object |
---|
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait |
Constructor Detail |
---|
public ClikJacobianTranspose(Robot robot, DMatrix Kp, DMatrix Ko)
robot
- the robot.Kp
- the diagonal matrix of error position gain.Ko
- the diagonal matrix of error orientationo gain.public ClikJacobianTranspose(Robot robot, DMatrix Kp, DMatrix Ko, double dt)
robot
- the robot.Kp
- the diagonal matrix of error position gain.Ko
- the diagonal matrix of error orientationo gain.dt
- the sample time.Method Detail |
---|
public void step(RVector3d pd, RVector3d ppd, Quaternion quatd, RVector3d wd)
step
in interface CLIK
step
in class ClikJacobianInverse
pd
- the vector of desired end effector position.ppd
- input parameter not considered.quatd
- the desired end effector quaternion.wd
- input parameter not considered.
|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |