Algorithms

Index

The DynamicsResult type

type DynamicsResult{M<:Number, T<:Number}

Stores variables related to the dynamics of a Mechanism, e.g. the Mechanism's mass matrix and joint acceleration vector.

Type parameters:

  • M: the scalar type of the Mechanism.

  • T: the scalar type of the dynamics-related variables.

source

Functions

center_of_mass(state, itr)

Compute the center of mass of an iterable subset of a Mechanism's bodies in the given state.

source
center_of_mass(state)

Compute the center of mass of the whole Mechanism in the given state.

source
dynamics!(result, state)
dynamics!(result, state, torques)
dynamics!(result, state, torques, externalwrenches)

Compute the joint acceleration vector $\dot{v}$ and Lagrange multipliers $\lambda$ that satisfy the joint-space equations of motion

\[M(q) \dot{v} + c(q, v, w_\text{ext}) = \tau - K(q)^{T} \lambda\]

and the constraint equations

\[K(q) \dot{v} = -k\]

given joint configuration vector $q$, joint velocity vector $v$, and (optionally) joint torques $\tau$ and external wrenches $w_\text{ext}$.

source
dynamics!(ẋ, result, state, stateVec, torques)
dynamics!(ẋ, result, state, stateVec)
dynamics!(ẋ, result, state, stateVec, torques, externalwrenches)

Convenience function for use with standard ODE integrators that takes a Vector argument

\[x = \left(\begin{array}{c} q\\ v \end{array}\right)\]

and returns a Vector $\dot{x}$.

source
geometric_jacobian(state, path)

Compute a geometric Jacobian (also known as a basic, or spatial Jacobian) for a path in the graph of joints and bodies of a Mechanism, in the given state.

See also path, GeometricJacobian.

source
gravitational_potential_energy(state)

Compute the gravitational potential energy in the given state, computed as the negation of the dot product of the gravitational force and the center of mass expressed in the Mechanism's root frame.

source
inverse_dynamics(state, v̇)
inverse_dynamics(state, v̇, externalwrenches)

Do inverse dynamics, i.e. compute $\tau$ in the unconstrained joint-space equations of motion

\[M(q) \dot{v} + c(q, v, w_\text{ext}) = \tau\]

given joint configuration vector $q$, joint velocity vector $v$, joint acceleration vector $\dot{v}$ and (optionally) external wrenches $w_\text{ext}$.

This method implements the recursive Newton-Euler algorithm.

Currently doesn't support Mechanisms with cycles.

source
inverse_dynamics!(torquesout, jointwrenchesOut, accelerations, state, v̇)
inverse_dynamics!(torquesout, jointwrenchesOut, accelerations, state, v̇, externalwrenches)

Do inverse dynamics, i.e. compute $\tau$ in the unconstrained joint-space equations of motion

\[M(q) \dot{v} + c(q, v, w_\text{ext}) = \tau\]

given joint configuration vector $q$, joint velocity vector $v$, joint acceleration vector $\dot{v}$ and (optionally) external wrenches $w_\text{ext}$.

This method implements the recursive Newton-Euler algorithm.

Currently doesn't support Mechanisms with cycles.

This method does its computation in place, performing no dynamic memory allocation.

source
mass(m)

Return the total mass of the Mechanism.

source
mass_matrix!(out, state)

Compute the joint-space mass matrix (also known as the inertia matrix) of the Mechanism in the given state, i.e., the matrix $M(q)$ in the unconstrained joint-space equations of motion

\[M(q) \dot{v} + c(q, v, w_\text{ext}) = \tau\]

This method implements the composite rigid body algorithm.

This method does its computation in place, performing no dynamic memory allocation.

The out argument must be an $n_v \times n_v$ lower triangular Symmetric matrix, where $n_v$ is the dimension of the Mechanism's joint velocity vector $v$.

source
mass_matrix(state)

Compute the joint-space mass matrix (also known as the inertia matrix) of the Mechanism in the given state, i.e., the matrix $M(q)$ in the unconstrained joint-space equations of motion

\[M(q) \dot{v} + c(q, v, w_\text{ext}) = \tau\]

This method implements the composite rigid body algorithm.

source
momentum_matrix!(out, state)

Compute the momentum matrix $A(q)$ of the Mechanism in the given state.

The momentum matrix maps the Mechanism's joint velocity vector $v$ to its total momentum.

This method does its computation in place, performing no dynamic memory allocation.

The out argument must be a mutable MomentumMatrix with as many columns as the dimension of the Mechanism's joint velocity vector $v$.

source
momentum_matrix(state)

Compute the momentum matrix $A(q)$ of the Mechanism in the given state.

The momentum matrix maps the Mechanism's joint velocity vector $v$ to its total momentum.

source
relative_acceleration(state, body, base, v̇)

Compute the spatial acceleration of body with respect to base for the given state and joint acceleration vector $\dot{v}$.

source
dynamics_bias!(torques, biasaccelerations, wrenches, state)
dynamics_bias!(torques, biasaccelerations, wrenches, state, externalwrenches)

Compute the 'dynamics bias term', i.e. the term

\[c(q, v, w_\text{ext})\]

in the unconstrained joint-space equations of motion

\[M(q) \dot{v} + c(q, v, w_\text{ext}) = \tau\]

This method does its computation in place, performing no dynamic memory allocation.

source
subtree_mass(base, mechanism)

Return the mass of a subtree of a Mechanism, rooted at base (including the mass of base).

source