Algorithms
Index
RigidBodyDynamics.DynamicsResult
RigidBodyDynamics.center_of_mass
RigidBodyDynamics.center_of_mass
RigidBodyDynamics.dynamics!
RigidBodyDynamics.dynamics!
RigidBodyDynamics.dynamics_bias!
RigidBodyDynamics.geometric_jacobian
RigidBodyDynamics.gravitational_potential_energy
RigidBodyDynamics.inverse_dynamics
RigidBodyDynamics.inverse_dynamics!
RigidBodyDynamics.mass
RigidBodyDynamics.mass_matrix
RigidBodyDynamics.mass_matrix!
RigidBodyDynamics.momentum_matrix
RigidBodyDynamics.momentum_matrix!
RigidBodyDynamics.relative_acceleration
RigidBodyDynamics.subtree_mass
The DynamicsResult
type
RigidBodyDynamics.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 theMechanism
.T
: the scalar type of the dynamics-related variables.
Functions
RigidBodyDynamics.center_of_mass
— Method.center_of_mass(state, itr)
Compute the center of mass of an iterable subset of a Mechanism
's bodies in the given state.
RigidBodyDynamics.center_of_mass
— Method.center_of_mass(state)
Compute the center of mass of the whole Mechanism
in the given state.
RigidBodyDynamics.dynamics!
— Function.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
and the constraint equations
given joint configuration vector $q$, joint velocity vector $v$, and (optionally) joint torques $\tau$ and external wrenches $w_\text{ext}$.
RigidBodyDynamics.dynamics!
— Function.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
and returns a Vector
$\dot{x}$.
RigidBodyDynamics.geometric_jacobian
— Method.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
.
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.
RigidBodyDynamics.inverse_dynamics
— Function.inverse_dynamics(state, v̇)
inverse_dynamics(state, v̇, externalwrenches)
Do inverse dynamics, i.e. compute $\tau$ in the unconstrained joint-space equations of motion
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 Mechanism
s with cycles.
RigidBodyDynamics.inverse_dynamics!
— Function.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
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 Mechanism
s with cycles.
This method does its computation in place, performing no dynamic memory allocation.
RigidBodyDynamics.mass
— Method.mass(m)
Return the total mass of the Mechanism
.
RigidBodyDynamics.mass_matrix!
— Method.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
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$.
RigidBodyDynamics.mass_matrix
— Method.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
This method implements the composite rigid body algorithm.
RigidBodyDynamics.momentum_matrix!
— Method.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$.
RigidBodyDynamics.momentum_matrix
— Method.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.
RigidBodyDynamics.relative_acceleration
— Method.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}$.
RigidBodyDynamics.dynamics_bias!
— Function.dynamics_bias!(torques, biasaccelerations, wrenches, state)
dynamics_bias!(torques, biasaccelerations, wrenches, state, externalwrenches)
Compute the 'dynamics bias term', i.e. the term
in the unconstrained joint-space equations of motion
This method does its computation in place, performing no dynamic memory allocation.
RigidBodyDynamics.subtree_mass
— Method.subtree_mass(base, mechanism)
Return the mass of a subtree of a Mechanism
, rooted at base
(including the mass of base
).