|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |
public interface CLIK
Closed Loop Inverse Kinematic algorithms interface for robots manipulator.
Method Summary | |
---|---|
double |
getEps()
Gets the singular region area. |
RVector |
getJointsPosition()
Gets the current joints position. |
RVector |
getJointsVelocity()
Gets the current joints velocity. |
DMatrix |
getKo()
Gets the matrix of error orientation gain. |
DMatrix |
getKp()
Gets the matrix of error position gain. |
double |
getLambdaMax()
Gets the maximum damped factor. |
RVector3d |
getOrientationError()
Gets the current orientation error. |
RVector3d |
getPositionError()
Gets the current position error. |
double |
getSampleTime()
Gets the sample time. |
void |
setEps(double eps)
Sets the singular region area. |
void |
setKo(DMatrix kd)
Sets the matrix of error orientation gain. |
void |
setKp(DMatrix kp)
Sets the matrix of error position gain. |
void |
setLambdaMax(double lambdaMax)
Sets the maximum damped factor. |
void |
setSampleTime(double h)
Sets the sample time. |
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. |
Method Detail |
---|
double getEps()
void setEps(double eps)
eps
- The eps to set.double getSampleTime()
void setSampleTime(double h)
h
- The sample time to set.DMatrix getKp()
void setKp(DMatrix kp)
kp
- The diagonal matrix to set.DMatrix getKo()
void setKo(DMatrix kd)
kd
- The diagonal matrix to set.double getLambdaMax()
void setLambdaMax(double lambdaMax)
lambdaMax
- The damped factor to set.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 getJointsPosition()
RVector getJointsVelocity()
void step(RVector3d pd, RVector3d ppd, Quaternion quatd, RVector3d wd)
pd
- the vector of desired end effector position.ppd
- the vector of desired end effector velocity.quatd
- the desired end effector quaternion.wd
- the desired end effector angular velocity.
|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |