Skip to content

Commit c71d6f7

Browse files
committed
improve kinematic loop docs
1 parent 0ec8390 commit c71d6f7

File tree

3 files changed

+22
-11
lines changed

3 files changed

+22
-11
lines changed

docs/src/examples/kinematic_loops.md

Lines changed: 21 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -2,11 +2,25 @@
22

33
Kinematic loops can be difficult to simulate since they introduce an over-constrained system. This tutorial demonstrates how to handle a few common cases of kinematic loops.
44

5+
Common for every kinematic loop is that the modeler must handle the redundant equations introduced by closing the loop. There are three main ways of doing this, listed in their general order of preference:
6+
1. Use a joint assembly, a component that combines several joints and solves the nonlinear equations analytically.
7+
2. Use a joint constraint rather than a joint (sometimes called and _implicit_ joint).
8+
3. Use a regular joint with the option `iscut = true` to indicate that the joint is a cut joint.
9+
10+
11+
Joint assemblies offer the possibility to analytically solve one or several nonlinear algebraic equations, such that the solver does not have to solve them with iterative methods. This generally provides a much faster simulation. Joint assemblies are components that consists of several joints with rigid bodies in between, such as [`SphericalSpherical`](@ref) and [`UniversalSpherical`](@ref).
12+
13+
Joint constraints work more or less like regular joints, but do not have state variables. In a kinematic loop, one joint may be changed to a joint constraint in order to simplify the nonlinear algebraic equations.
14+
15+
If no joint assembly or constraint that simplify the loop is available, one joint in each loop must be marked as `iscut = true`. This indicates that the loop is closed using a smaller number of residual equations rather than the full number of orientation constraints implied by equality between rotation matrices.
16+
17+
18+
519
## A planar kinematic loop
620

7-
A planar loop is one where the loop is confined to a plane, i.e., all joints in the loop have parallel rotation axes. To simulate a mechanism with such a loop, we break the kinematic loop by replacing one of the revolute joints with a [`RevolutePlanarLoopConstraint`](@ref). The model below contains four bars connected by revolute joints, forming a planar loop. In order to make the animation interesting, we attach dampers to two of the joints such that the mechanism will oscillate for a while before coming to rest.
21+
A planar loop is one where the loop is confined to a plane, i.e., all joints in the loop have parallel rotation axes. To simulate a mechanism with such a loop, we break the kinematic loop by replacing one of the revolute joints with a [`RevolutePlanarLoopConstraint`](@ref). The reason is that, e.g., the cut forces in direction of the axes of the revolute joints cannot be uniquely computed. The model below contains four bars connected by revolute joints, forming a planar loop. In order to make the animation interesting, we attach dampers to two of the joints such that the mechanism will oscillate for a while before coming to rest.
822

9-
Perhaps surprisingly, we use 5 joints in total for this mechanism. If we had used four joints only and connected the first frame of the first joint to the world, the mechanism would not be free to rotate around the world frame. We thus have two joints connected to the world frame below.
23+
Perhaps surprisingly, we use 5 joints in total for this mechanism. If we had used four joints only and connected the first frame of the first joint to the world, the mechanism would not be free to rotate around the world frame. We thus have two joints connected to the world frame below. Exactly one revolute joint is changed into a [`RevolutePlanarLoopConstraint`](@ref) to break the planar loop.
1024

1125
```@example kinloop
1226
using Multibody
@@ -91,7 +105,11 @@ nothing # hide
91105

92106
## Using cut joints
93107

94-
The mechanism below is another instance of a 4-bar linkage, this time with 6 revolute joints, 1 prismatic joint and 4 bodies. In order to simulate this mechanism, the user must
108+
The mechanism below is another instance of a 4-bar linkage, this time with 6 revolute joints, 1 prismatic joint and 4 bodies.
109+
110+
We show two different ways of modeling this mechanism, first using a cut joint, and later using a much more efficient joint assembly.
111+
112+
In order to simulate this mechanism using a cut joint, the user must
95113
1. Use the `iscut=true` keyword argument to one of the `Revolute` joints to indicate that the joint is a cut joint. A cut joint behaves similarly to a regular joint, but it introduces fewer constraints in order to avoid the otherwise over-constrained system resulting from closing the kinematic loop. While almost any joint can be chosen as the cut joint, it might be worthwhile experimenting with this choice in order to get an efficient representation. In this example, cutting `j5` produces an 8-dimensional state realization, while all other joints result in a 17-dimensional state.
96114
2. Increase the `state_priority` of the joint `j1` above the default joint priority 3. This encourages the model compiler to choose the joint coordinate of `j1` as state variable. The joint coordinate of `j1` is the only coordinate that uniquely determines the configuration of the mechanism. The choice of any other joint coordinate would lead to a singular representation in at least one configuration of the mechanism. The joint `j1` is the revolute joint located in the origin, see the animation below where this joint is made larger than the others.
97115

src/joints.jl

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -576,7 +576,7 @@ Revolute joint that is described by 2 positional constraints for usage in a plan
576576
577577
Joint where `frame_b` rotates around axis `n` which is fixed in `frame_a` and where this joint is used in a planar loop providing 2 constraint equations on position level.
578578
579-
If a planar loop is present, e.g., consisting of 4 revolute joints where the joint axes are all parallel to each other, then there is no unique mathematical solution if all revolute joints are modelled with `Revolute` and the symbolic algorithms will fail. The reason is that, e.g., the cut-forces in the revolute joints perpendicular to the planar loop are not uniquely defined when 3-dim. descriptions of revolute joints are used. Usually, an error message will be printed pointing out this situation. In this case, one revolute joint in the loop has to be replaced by model `RevolutePlanarLoopCutJoint`. The effect is that from the 5 constraints of a 3-dim. revolute joint, 3 constraints are removed and replaced by appropriate known variables (e.g., the force in the direction of the axis of rotation is treated as known with value equal to zero; for standard revolute joints, this force is an unknown quantity).
579+
If a planar loop is present, e.g., consisting of 4 revolute joints where the joint axes are all parallel to each other, then there is no unique mathematical solution if all revolute joints are modelled with [`Revolute`](@ref) and the symbolic algorithms will fail. The reason is that, e.g., the cut-forces in the revolute joints perpendicular to the planar loop are not uniquely defined when 3-dim. descriptions of revolute joints are used. In this case, one revolute joint in the loop has to be replaced by model `RevolutePlanarLoopConstraint`. The effect is that from the 5 constraints of a 3-dim. revolute joint, 3 constraints are removed and replaced by appropriate known variables (e.g., the force in the direction of the axis of rotation is treated as known with value equal to zero; for standard revolute joints, this force is an unknown quantity).
580580
"""
581581
@component function RevolutePlanarLoopConstraint(; name, n = Float64[0, 0, 1], radius = 0.05, length = radius, color = [0.5019608f0,0.0f0,0.5019608f0,1.0f0])
582582
norm(n) 1 || error("Axis of rotation must be a unit vector")

src/orientation.jl

Lines changed: 0 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -247,13 +247,6 @@ function residue(R1, R2)
247247
# ]
248248
end
249249

250-
function connect_loop(F1, F2)
251-
F1.metadata[:loop_opening] = true
252-
# connect(F1, F2)
253-
# orientation_constraint(ori(F1)'ori(F2)) .~ 0
254-
residue(F1, F2) .~ 0
255-
end
256-
257250
## Quaternions
258251

259252

0 commit comments

Comments
 (0)