- 
                Notifications
    You must be signed in to change notification settings 
- Fork 540
Kinematics
Forward kinematics (FK) is the pose of the end-effector given the joint coordinates.
It can be computed for robots of the DHRobot or ERobot class
T = robot.fkine(q)
where T is an SE3 instance.
T = robot.fkine_all(q)
where T is an SE3 instance with multiple values, the pose of each link frame, from the base T[0] to the end-effector T[-1].
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.
| Method | MATLAB version | Type | Joint limits | Description | 
|---|---|---|---|---|
| ikine_a | ikine6s | analytic | no | For specific DHRobots only | 
| ikine_LM | ikine | numeric | no | Levenberg-Marquadt with global search option | 
| ikine_LMS | numeric | no | Levenberg-Marquadt with Sugihara's tweak | |
| ikine_unc | ikunc | numeric | no | Uses SciPy.minimize | 
| ikine_con | ikcon | numeric | yes | Uses SciPy.minimize | 
| ikine_min | ikinem | numeric | no | Uses SciPy.minimize | 
| ikine_QP | numeric | no | Uses quadprog | 
All methods take optional method-specific arguments and return a named tuple
sol = ikine_XX(T)
The elements of the tuple sol include at least:
| Element | Type | Description | 
|---|---|---|
| q | ndarray (n) | Joint coordinates for the solution, or None | 
| success | bool | Trueif a solution found | 
| reason | str | reason for failure | 
| iterations | int | number of iterations | 
| residual | float | final value of cost function | 
puma = rtb.models.DH.Puma560()
T = puma.fkine(puma.qn)
sol = puma.ikine_XX(T)
| Method | Time (ms) | Residual | 
|---|---|---|
| ikine_a | 0.34 | 0 | 
| ikine_LM | 6.6 | 8.8e-11 | 
| ikine_LMS | 3.8 | 2.3e-6 | 
| ikine_unc | 180 | 4.2e-6 | 
| ikine_con | 73 | 7.2e-6 | 
| ikine_min | 131 | 1.0e-5 | 
The SciPy based mimimizers are slow because they use a scalar cost measure and must numerically compute a Jacobian in order to solve.
This is just speculation so far...
T = robot.fkine(q, link)
where link is either a reference to a Link subclass object, or the name of the link.
q = robot.ikine_XX(T, link)
where link 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.
- Frequently asked questions (FAQ)
- Documentation Style Guide
- Typing Style Guide
- Background
- Key concepts
- Introduction to robot and link classes
- Working with Jupyter
- Working from the command line
- What about Simulink?
- How to contribute
- Common Issues
- Contributors