|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |
java.lang.Object javax.robotics.engine.clik.ClikJacobianPosInverse
public class ClikJacobianPosInverse
Closed Loop Inverse Kinematics with positional Jacobian inverse. The class
implements the same scheme depicted in
ClikJacobianInverse
:
The inverse is computed using SVD decomposition:
J-1 = JT*(J*JT + λ2*I)-1 where λ2 is the damped factor equals 1 - (σr/ε)*λ2max if σr< ε, equals 0 if σr≥ ε; σr is the smallest not null singular value.
The orientation error is not computed.
The integration method used is the forward Euler.
the solution without velocity
constraint.
,
the solution
with velocity constraint.
Constructor Summary | |
---|---|
ClikJacobianPosInverse(Robot robot,
DMatrix Kp)
Costructor with default sample time, dt = 1e-3 and eps = 0.02, lambdaMax=0.02, the space dimension = 3. |
|
ClikJacobianPosInverse(Robot robot,
DMatrix Kp,
double dt,
int spaceDim,
double eps,
double lambdaMax)
Constructor. |
|
ClikJacobianPosInverse(Robot robot,
DMatrix Kp,
int spaceDim)
Costructor with default sample time, dt = 1e-3 and eps = 0.02, lambdaMax=0.02. |
|
ClikJacobianPosInverse(Robot robot,
DMatrix Kp,
int spaceDim,
double dt)
Costructor with eps = 0.02, lambdaMax=0.02. |
Method Summary | |
---|---|
int |
getCartesianSpaceDim()
Gets the dimension of cartesian space. |
double |
getEps()
Gets the singular region area. |
RVector |
getJointsPosition()
Gets the current joints position. |
RVector |
getJointsVelocity()
Gets the current joints velocity. |
DMatrix |
getKp()
Gets the matrix of error position gain. |
double |
getLambdaMax()
Gets the maximum damped factor. |
RVector3d |
getPositionError()
Gets the current position error. |
double |
getSampleTime()
Gets the sample time. |
void |
setEps(double eps)
Sets the singular region area. |
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(RVector pd,
RVector ppd)
Compute the joints position and velocity from a given desired end effector position and velocity. |
void |
step(RVector pd,
RVector ppd,
ConstraintVelocity constraint)
Compute the joints position and velocity from a given desired end effector position and velocity with velocity constraint. |
Methods inherited from class java.lang.Object |
---|
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait |
Constructor Detail |
---|
public ClikJacobianPosInverse(Robot robot, DMatrix Kp)
robot
- the robot.Kp
- the diagonal matrix of error position gain.public ClikJacobianPosInverse(Robot robot, DMatrix Kp, int spaceDim)
robot
- the robot.Kp
- the diagonal matrix of error position gain.spaceDim
- the dimension of robot operational space.public ClikJacobianPosInverse(Robot robot, DMatrix Kp, int spaceDim, double dt)
robot
- the robot.Kp
- the diagonal matrix of error position gain.spaceDim
- the dimension of robot operational space.dt
- the sample time.public ClikJacobianPosInverse(Robot robot, DMatrix Kp, double dt, int spaceDim, double eps, double lambdaMax)
robot
- the robot.Kp
- the diagonal matrix of error position gain.spaceDim
- the dimension of robot operational space.dt
- the sample time.eps
- the area of singular region.lambdaMax
- the maximum of damped factor.Method Detail |
---|
public final int getCartesianSpaceDim()
CLIKR
getCartesianSpaceDim
in interface CLIKR
public final double getEps()
CLIKR
getEps
in interface CLIKR
public final void setEps(double eps)
CLIKR
setEps
in interface CLIKR
eps
- The eps to set.public final double getSampleTime()
CLIKR
getSampleTime
in interface CLIKR
public final void setSampleTime(double h)
CLIKR
setSampleTime
in interface CLIKR
h
- The sample time to set.public final DMatrix getKp()
CLIKR
getKp
in interface CLIKR
public final void setKp(DMatrix kp)
CLIKR
setKp
in interface CLIKR
kp
- The diagonal matrix to set.public final double getLambdaMax()
CLIKR
getLambdaMax
in interface CLIKR
public final void setLambdaMax(double lambdaMax)
CLIKR
setLambdaMax
in interface CLIKR
lambdaMax
- The damped factor to set.public final RVector3d getPositionError()
CLIKR
getPositionError
in interface CLIKR
public final RVector getJointsPosition()
getJointsPosition
in interface CLIKR
public final RVector getJointsVelocity()
getJointsVelocity
in interface CLIKR
public void step(RVector pd, RVector ppd)
step
in interface CLIKR
pd
- the RVector of desired end effector position.ppd
- the RVector of desired end effector velocity.public void step(RVector pd, RVector ppd, ConstraintVelocity constraint)
step
in interface CLIKR
pd
- the RVector of desired end effector position.ppd
- the RVector of desired end effector velocity.constraint
- the velocity constraint class.ConstraintVelocity
|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |