Skip to content

Commit

Permalink
docs updates
Browse files Browse the repository at this point in the history
  • Loading branch information
baggepinnen committed Jun 15, 2024
1 parent 1f04f99 commit 803a79d
Show file tree
Hide file tree
Showing 6 changed files with 5 additions and 11 deletions.
5 changes: 2 additions & 3 deletions docs/src/examples/pendulum.md
Original file line number Diff line number Diff line change
@@ -1,8 +1,6 @@
# Pendulum--The "Hello World of multi-body dynamics"
This beginners tutorial will model a pendulum pivoted around the origin in the world frame. The world frame is a constant that lives inside the Multibody module, all multibody models are "grounded" in the same world, i.e., the `world` component must be included in all models.

![Pendulum](https://doc.modelica.org/Modelica%203.2.3/Resources/Images/Mechanics/MultiBody/Examples/Elementary/Pendulum.png)

To start, we load the required packages
```@example pendulum
using ModelingToolkit
Expand Down Expand Up @@ -110,7 +108,6 @@ nothing # hide
When we think of a pendulum, we typically think of a rotary pendulum that is rotating around a pivot point like in the examples above.
A mass suspended in a spring can be though of as a linear pendulum (often referred to as a harmonic oscillator rather than a pendulum), and we show here how we can construct a model of such a device. This time around, we make use of a [`Prismatic`](@ref) joint rather than a [`Revolute`](@ref) joint. A [prismatic joint](https://en.wikipedia.org/wiki/Prismatic_joint) has one positional degree of freedom, compared to the single rotational degree of freedom for the revolute joint.

![Spring with mass](https://doc.modelica.org/Modelica%203.2.3/Resources/Images/Mechanics/MultiBody/Examples/Elementary/SpringWithMass.png)

```@example pendulum
@named body_0 = Body(; m = 1, isroot = false, r_cm = [0, 0, 0])
Expand Down Expand Up @@ -255,6 +252,8 @@ using Multibody.Rotations
(rotation_axis(R1), rotation_angle(R1))
```

Here, we made use of the function [`get_rot`](@ref), we will now make use of also [`get_trans`](@ref) and [`get_frame`](@ref).

The next body is the upper arm. This body has an extent of `0.6` in the $z$ direction, as measured in its local `frame_a`
```@example pendulum
get_trans(sol, model.upper_arm.frame_b, 0)
Expand Down
2 changes: 0 additions & 2 deletions docs/src/examples/spring_damper_system.md
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,6 @@ Welcome to the spring-damper system example, where we will show you the process

This tutorial mirrors that of the following Modelica tutorial [Spring damper system](https://doc.modelica.org/om/Modelica.Mechanics.MultiBody.Examples.Elementary.SpringDamperSystem.html) and demonstrates that a body can be freely moving without any connection to a joint. In this case body coordinates are used as state by setting the option `isroot=true` to the body.

![Spring-damper system](https://doc.modelica.org/Modelica%203.2.3/Resources/Images/Mechanics/MultiBody/Examples/Elementary/SpringDamperSystem.png)

This example has two parallel spring-mass parts, the first body (`body1`) is attached directly to the spring, with no joint in parallel with the spring. In this situation, we have to set `isroot=true` for `body1` to indicate that we want to use the body variables as state. The second body (`body2`) is attached to the spring with a joint in parallel with the spring, so we can use the joint variables as state, hence `isroot=false` for `body2`.

```@example spring_damper_system
Expand Down
1 change: 0 additions & 1 deletion docs/src/examples/spring_mass_system.md
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@ This example mirrors that of the [modelica spring-mass system](https://doc.model
1. Using a prismatic joint and a 1-dimensional spring from the `Translational` submodule attached to the joint. The advantage of this approach is that the many elements from the Translational library can be easily used here and that this implementation is usually more efficient compared to when using 3-dimensional springs.
2. Using a 3-dimensional spring from the `Multibody` library.

![Spring-mass system](https://doc.modelica.org/Modelica%203.2.3/Resources/Images/Mechanics/MultiBody/Examples/Elementary/SpringMassSystem.png)

```@example spring_mass_system
using Multibody
Expand Down
2 changes: 0 additions & 2 deletions docs/src/examples/three_springs.md
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,6 @@

This example mirrors that of the [modelica three-springs](https://doc.modelica.org/om/Modelica.Mechanics.MultiBody.Examples.Elementary.ThreeSprings.html) and demonstrates that we can connect mass-less force elements together.

![three springs](https://doc.modelica.org/Modelica%203.2.3/Resources/Images/Mechanics/MultiBody/Examples/Elementary/ThreeSprings.png)



The example connects three springs together in a single point. The springs are all massless and do normally not have any state variables, but we can insist on one of the springs being stateful, in this case, we must tell the lower spring component to act as root by setting `fixed_rotation_at_frame_a = fixed_rotation_at_frame_b = true`.
Expand Down
2 changes: 1 addition & 1 deletion docs/src/index.md
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ In this documentation, you will find everything you need to get started with Mul



## Notable difference from Modelica
## Notable differences from Modelica

- The torque variable in Multibody.jl is typically called `tau` rather than `t` to not conflict with the often used independent variable `t` used to denote time.
- Multibody.jl occasionally requires the user to specify which component should act as the root of the kinematic tree. This only occurs when bodies are connected directly to force components without a joint parallel to the force component.
Expand Down
4 changes: 2 additions & 2 deletions src/orientation.jl
Original file line number Diff line number Diff line change
Expand Up @@ -427,7 +427,7 @@ Extract a 3×3 rotation matrix ∈ SO(3) from a solution at time `t`.
The rotation matrix returned, ``R_W^F``, is such that when a vector ``p_F`` expressed in the local `frame` of reference ``F`` is multiplied by ``R_W^F`` as ``Rp``, the resulting vector is ``p_W`` expressed in the world frame:
```math
p_W = R_W^F * p_F
p_W = R_W^F p_F
```
See also [`get_trans`](@ref), [`get_frame`](@ref), [Orientations and directions](@ref) (docs section).
Expand All @@ -453,7 +453,7 @@ Extract a 4×4 transformation matrix ∈ SE(3) from a solution at time `t`.
The transformation matrix returned, ``T_W^F``, is such that when a homogenous-coordinate vector ``p_F``, expressed in the local `frame` of reference ``F`` is multiplied by ``T_W^F`` as ``Tp``, the resulting vector is ``p_W`` expressed in the world frame:
```math
p_W = T_W^F * p_F
p_W = T_W^F p_F
```
See also [`get_trans`](@ref) and [`get_rot`](@ref), [Orientations and directions](@ref) (docs section).
Expand Down

0 comments on commit 803a79d

Please sign in to comment.