-
Notifications
You must be signed in to change notification settings - Fork 509
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_min |
ikunc |
numeric | no | Uses SciPy.minimize, user cost function, stiffness |
ikine_min(qlim=True) |
ikcon |
numeric | yes | Uses 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 tuple sol
include at least:
Element | Type | Description |
---|---|---|
q |
ndarray (n) | Joint coordinates for the solution, or None
|
success |
bool |
True if 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)
print("residual = ", np.linalg.norm(T - puma.fkine(sol.q)))
Method | Time (ms) | Residual |
---|---|---|
ikine_a |
0.34 | 1.5e-16 |
ikine_LM |
6.9 | 8.8e-11 |
ikine_LMS |
3.8 | 2.2e-6 |
ikine_unc |
45 | 1.3e-7 |
ikine_min |
1500 | 1.0e-5 |
ikine_min(qlim=True) |
131 | 1.0e-5 |
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)))
Method | Time (ms) | Residual |
---|---|---|
ikine_LM |
9.1 | 1.5e-11 |
ikine_LMS |
11 | 3.6e-6 |
ikine_min |
75 | 4.5e-8 |
ikine_min(qlim=True) |
1600 | 1.6e-7 |
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