Movatterモバイル変換


[0]ホーム

URL:


Skip to content

Navigation Menu

Sign in
Appearance settings

Search code, repositories, users, issues, pull requests...

Provide feedback

We read every piece of feedback, and take your input very seriously.

Saved searches

Use saved searches to filter your results more quickly

Sign up
Appearance settings

Kinematics

Peter Corke edited this pageJan 24, 2021 ·9 revisions

Forward kinematics

Forward kinematics (FK) is the pose of the end-effector given the joint coordinates.It can be computed for robots of theDHRobot orERobot class

T = robot.fkine(q)

whereT is anSE3 instance.

T = robot.fkine_all(q)

whereT is anSE3 instance with multiple values, the pose of each link frame, from the baseT[0] to the end-effectorT[-1].

Inverse kinematics

Inverse kinematics (IK) is the joint coordinates required to achieve a given end-effector pose. The function is not unique, and there may be no solution.

MethodMATLAB versionTypeJoint limitsDescription
ikine_aikine6sanalyticnoFor specific DHRobots only
ikine_LMikinenumericnoLevenberg-Marquadt with global search option
ikine_LMSnumericnoLevenberg-Marquadt with Sugihara's tweak
ikine_minikuncnumericnoUses SciPy.minimize, user cost function, stiffness
ikine_min(qlim=True)ikconnumericyesUses SciPy.minimize, user cost function, stiffness

All methods take optional method-specific arguments and return a named tuple

sol = ikine_XX(T)

The elements of the tuplesol include at least:

ElementTypeDescription
qndarray (n)Joint coordinates for the solution, orNone
successboolTrue if a solution found
reasonstrreason for failure
iterationsintnumber of iterations
residualfloatfinal value of cost function

Numerical solutions

These IK solvers minimise a scalar measure of error between the current and the desired end-effector pose. The measure is the squared-norm of a 6-vector comprising:

  • translational error (a 3-vector)
  • the orientation error as an Euler vector (angle/axis form encoded as a 3-vector)

The SciPy based mimimizers are slow because they use a scalar cost measure and must numerically compute a Jacobian in order to solve.

Performance

6DOF robot

puma=rtb.models.DH.Puma560()T=puma.fkine(puma.qn)sol=puma.ikine_XX(T)print("residual = ",np.linalg.norm(T-puma.fkine(sol.q)))
OperationTime (ms)Error
ikine_a0.352.23e-16
ikine_LM7.88.79e-11
ikine_LMS4.52.28e-06
ikine_min(qlim=False)451.29e-07
ikine_min(qlim=True)1.6e+031.56e-07

Forikine_min without joint limits we can request different optimization methods (the default isSLSQP) to be used

SolverTime (μs)Error
Nelder-Mead2.9e+020.0988
Powell6.5e+023.53e-12
CG2.9e+021.27e-07
BFGS1.2e+021.28e-07
L-BFGS-B641e-07
TNC1.7e+020.00559
SLSQP441.29e-07
trust-constr2.3e+021.45e-07

The methodsNewton-CG,dogleg,trust-ncg,trust-exact,trust-krylov all require a Jacobian matrix to be passed.

Forikine_minwith joint limits we can request different optimization methods (the default istrust-constr) to be used

SolverTime (ms)Error
Powell6.5e+021.94e-12
L-BFGS-B671.03e-07
TNC1.7e+020.04
SLSQP481.35e-07
trust-constr1.6e+031.56e-07

Interesting attempting constrained optimisation using methodsNelder-Mead,CG,BFGS does not raise an error, they just silently ignore the constraints. Once again, the methodsNewton-CG,dogleg,trust-ncg,trust-exact,trust-krylov all require a Jacobian matrix to be passed.

7DOF robot

puma=Panda()T=SE3(0.7,0.2,0.1)*SE3.OA([0,1,0], [0,0,-1])sol=puma.ikine_XX(T)print("residual = ",np.linalg.norm(T-puma.fkine(sol.q)))
MethodTime (ms)Residual
ikine_LM9.11.5e-11
ikine_LMS113.6e-6
ikine_min754.5e-8
ikine_min(qlim=True)16001.6e-7

Analytical solutions

Only theDH/Puma560 robot model has an analytic solution methodikine_a(T, config).

Such a method could be added to any other robot class, including anycustom class that you might write.

For the class of robots that have 6 joints and a spherical wrist, the Toolbox provides additional support. First define a method in your class

def ikine_a(self, T, config):    return self.ikine_6s(T, config, func)

where:

  • ikine_6s is a method of theDHRobot class
  • func is a local functionfunc(robot, T, config) that solves for the first three joints, givenT which is the pose of the wrist centre with respect to the base.
  • config is a pose configuration string. For example, the Puma robot defines this as
LetterMeaning
lChoose the left-handed configuration
rChoose the right-handed configuration
uChoose the elbow up configuration
dChoose the elbow down configuration
nChoose the wrist not-flipped configuration
fChoose the wrist flipped configuration

but you can choose whatever is appropriate for your robot.

Base and tool transforms

All robot classes support abase transform. This defines the pose of the robot's base with respect to the world frame and is by default null transform (identity matrix).

DHRobot objects support atool transform. This defines the tip of the robot's end-effector with respect to the final link frame, which is typically inside the spherical wrist. By default this is a null transform (identity matrix).Note that some robot models describe the tool transform using DH parameters, seeSection 5 of this tutorial.

Joint offsets

DHRobot support a joint offset which is important since often the required zero-angle configuration is not what the user or robot controller considers the zero-angle configuration, due to the constraints imposed by DH notation.

For forward kinematics the joint offsets are added to yield the "kinematic" joint angles, and then the forward kinematics are computed. This occurs within theA method of theDHLink class. This means that the offsets are the kinematic joints angles corresponding to the user's zero-angle configuration.

Jacobian calculation use theA method so joint offsets are taken into consideration.

Numerical inverse kinematics use thefkine method so joint offsets are taken into consideration. Analytical inverse kinematics explicitlysubtract the offset in theikine_6s method.

Robots with multiple end effectors

This is just speculation so far...

T = robot.fkine(q, link)

wherelink is either a reference to a Link subclass object, or the name of the link.

q = robot.ikine_XX(T, link)

wherelink is either a reference to a Link subclass object, or the name of the link.

Ideally we would be able to express other constraints by passing in a callable

q = robot.ikine_XX(T, lambda q: 0.1 * q[2]**2)

which adds a cost for elbow bend, for example.

Clone this wiki locally


[8]ページ先頭

©2009-2025 Movatter.jp