Algorithms
Index
RigidBodyDynamics.DynamicsResult
RigidBodyDynamics.Spatial.center_of_mass
RigidBodyDynamics.Spatial.center_of_mass
RigidBodyDynamics._point_jacobian!
RigidBodyDynamics.default_constraint_stabilization_gains
RigidBodyDynamics.dynamics!
RigidBodyDynamics.dynamics!
RigidBodyDynamics.dynamics_bias
RigidBodyDynamics.dynamics_bias!
RigidBodyDynamics.geometric_jacobian
RigidBodyDynamics.geometric_jacobian!
RigidBodyDynamics.geometric_jacobian!
RigidBodyDynamics.geometric_jacobian!
RigidBodyDynamics.inverse_dynamics
RigidBodyDynamics.inverse_dynamics!
RigidBodyDynamics.mass
RigidBodyDynamics.mass_matrix
RigidBodyDynamics.mass_matrix!
RigidBodyDynamics.momentum_matrix
RigidBodyDynamics.momentum_matrix!
RigidBodyDynamics.momentum_matrix!
RigidBodyDynamics.momentum_matrix!
RigidBodyDynamics.point_jacobian
RigidBodyDynamics.point_jacobian!
RigidBodyDynamics.subtree_mass
The DynamicsResult
type
RigidBodyDynamics.DynamicsResult
— Typemutable struct DynamicsResult{T, M}
Stores variables related to the dynamics of a Mechanism
, e.g. the Mechanism
's mass matrix and joint acceleration vector.
Type parameters:
T
: the scalar type of the dynamics-related variables.M
: the scalar type of theMechanism
.
Functions
RigidBodyDynamics.Spatial.center_of_mass
— Methodcenter_of_mass(state, itr)
Compute the center of mass of an iterable subset of a Mechanism
's bodies in the given state. Ignores the root body of the mechanism.
RigidBodyDynamics.Spatial.center_of_mass
— Methodcenter_of_mass(state)
Compute the center of mass of the whole Mechanism
in the given state.
RigidBodyDynamics._point_jacobian!
— Method_point_jacobian!(Jp, state, path, point, transformfun)
Compute the Jacobian mapping the Mechanism
's joint velocity vector $v$ to the velocity of a point fixed to the target of the joint path (the body succeeding the last joint in the path) with respect to the source of the joint path (the body preceding the first joint in the path).
This method does its computation in place, performing no dynamic memory allocation.
RigidBodyDynamics.default_constraint_stabilization_gains
— MethodReturn the default Baumgarte constraint stabilization gains. These gains result in critical damping, and correspond to $T_{stab} = 0.1$ in Featherstone (2008), section 8.3.
RigidBodyDynamics.dynamics!
— Methoddynamics!(result, state)
dynamics!(result, state, torques)
dynamics!(result, state, torques, externalwrenches; stabilization_gains)
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}$.
The externalwrenches
argument can be used to specify additional wrenches that act on the Mechanism
's bodies.
The stabilization_gains
keyword argument can be used to set PD gains for Baumgarte stabilization, which can be used to prevent separation of non-tree (loop) joints. See Featherstone (2008), section 8.3 for more information. There are several options for specifying gains:
nothing
can be used to completely disable Baumgarte stabilization.- Gains can be specifed on a per-joint basis using any
AbstractDict{JointID, <:RigidBodyDynamics.PDControl.SE3PDGains}
, which maps theJointID
for the non-tree joints of the mechanism to the gains for that joint. - As a special case of the second option, the same gains can be used for all joints by passing in a
RigidBodyDynamics.CustomCollections.ConstDict{JointID}
.
The default_constraint_stabilization_gains
function is called to produce the default gains, which use the last option.
RigidBodyDynamics.dynamics!
— Methoddynamics!(ẋ, result, state, x)
dynamics!(ẋ, result, state, x, torques)
dynamics!(ẋ, result, state, x, torques, externalwrenches; stabilization_gains)
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}$.
RigidBodyDynamics.dynamics_bias!
— Methoddynamics_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\]
given joint configuration vector $q$, joint velocity vector $v$, joint acceleration vector $\dot{v}$ and (optionally) external wrenches $w_\text{ext}$.
The externalwrenches
argument can be used to specify additional wrenches that act on the Mechanism
's bodies.
This method does its computation in place, performing no dynamic memory allocation.
RigidBodyDynamics.dynamics_bias
— Methoddynamics_bias(state)
dynamics_bias(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\]
given joint configuration vector $q$, joint velocity vector $v$, joint acceleration vector $\dot{v}$ and (optionally) external wrenches $w_\text{ext}$.
The externalwrenches
argument can be used to specify additional wrenches that act on the Mechanism
's bodies.
RigidBodyDynamics.geometric_jacobian!
— Methodgeometric_jacobian!(jac, state, path, transformfun)
Compute a geometric Jacobian (also known as a basic, or spatial Jacobian) associated with a directed path in the Mechanism
's spanning tree, (a collection of Joint
s and traversal directions) in the given state.
A geometric Jacobian maps the Mechanism
's joint velocity vector $v$ to the twist of the target of the joint path (the body succeeding the last joint in the path) with respect to the source of the joint path (the body preceding the first joint in the path).
See also path
, GeometricJacobian
, Twist
.
transformfun
is a callable that may be used to transform the individual motion subspaces of each of the joints to the frame in which out
is expressed.
This method does its computation in place, performing no dynamic memory allocation.
RigidBodyDynamics.geometric_jacobian!
— Methodgeometric_jacobian!(out, state, path, root_to_desired)
Compute a geometric Jacobian (also known as a basic, or spatial Jacobian) associated with a directed path in the Mechanism
's spanning tree, (a collection of Joint
s and traversal directions) in the given state.
A geometric Jacobian maps the Mechanism
's joint velocity vector $v$ to the twist of the target of the joint path (the body succeeding the last joint in the path) with respect to the source of the joint path (the body preceding the first joint in the path).
See also path
, GeometricJacobian
, Twist
.
root_to_desired
is the transform from the Mechanism
's root frame to the frame in which out
is expressed.
This method does its computation in place, performing no dynamic memory allocation.
RigidBodyDynamics.geometric_jacobian!
— Methodgeometric_jacobian!(out, state, path)
Compute a geometric Jacobian (also known as a basic, or spatial Jacobian) associated with a directed path in the Mechanism
's spanning tree, (a collection of Joint
s and traversal directions) in the given state.
A geometric Jacobian maps the Mechanism
's joint velocity vector $v$ to the twist of the target of the joint path (the body succeeding the last joint in the path) with respect to the source of the joint path (the body preceding the first joint in the path).
See also path
, GeometricJacobian
, Twist
.
See geometric_jacobian!(out, state, path, root_to_desired)
. Uses state
to compute the transform from the Mechanism
's root frame to the frame in which out
is expressed.
This method does its computation in place, performing no dynamic memory allocation.
RigidBodyDynamics.geometric_jacobian
— Methodgeometric_jacobian(state, path)
Compute a geometric Jacobian (also known as a basic, or spatial Jacobian) associated with a directed path in the Mechanism
's spanning tree, (a collection of Joint
s and traversal directions) in the given state.
A geometric Jacobian maps the Mechanism
's joint velocity vector $v$ to the twist of the target of the joint path (the body succeeding the last joint in the path) with respect to the source of the joint path (the body preceding the first joint in the path).
See also path
, GeometricJacobian
, Twist
.
The Jacobian is computed in the Mechanism
's root frame.
RigidBodyDynamics.inverse_dynamics!
— Methodinverse_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}$.
The externalwrenches
argument can be used to specify additional wrenches that act on the Mechanism
's bodies.
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.inverse_dynamics
— Methodinverse_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}$.
The externalwrenches
argument can be used to specify additional wrenches that act on the Mechanism
's bodies.
This method implements the recursive Newton-Euler algorithm.
Currently doesn't support Mechanism
s with cycles.
RigidBodyDynamics.mass
— Methodmass(m)
Return the total mass of the Mechanism
.
RigidBodyDynamics.mass_matrix!
— Methodmass_matrix!(M, 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$.
RigidBodyDynamics.mass_matrix
— MethodCompute 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.
RigidBodyDynamics.momentum_matrix!
— Methodmomentum_matrix!(mat, state, transformfun)
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.
See also MomentumMatrix
.
The out
argument must be a mutable MomentumMatrix
with as many columns as the dimension of the Mechanism
's joint velocity vector $v$.
transformfun
is a callable that may be used to transform the individual momentum matrix blocks associated with each of the joints to the frame in which out
is expressed.
This method does its computation in place, performing no dynamic memory allocation.
RigidBodyDynamics.momentum_matrix!
— Methodmomentum_matrix!(mat, state, root_to_desired)
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.
See also MomentumMatrix
.
The out
argument must be a mutable MomentumMatrix
with as many columns as the dimension of the Mechanism
's joint velocity vector $v$.
root_to_desired
is the transform from the Mechanism
's root frame to the frame in which out
is expressed.
This method does its computation in place, performing no dynamic memory allocation.
RigidBodyDynamics.momentum_matrix!
— Methodmomentum_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.
See also MomentumMatrix
.
The out
argument must be a mutable MomentumMatrix
with as many columns as the dimension of the Mechanism
's joint velocity vector $v$.
See momentum_matrix!(out, state, root_to_desired)
. Uses state
to compute the transform from the Mechanism
's root frame to the frame in which out
is expressed.
This method does its computation in place, performing no dynamic memory allocation.
RigidBodyDynamics.momentum_matrix
— Methodmomentum_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.
See also MomentumMatrix
.
RigidBodyDynamics.point_jacobian!
— Methodpoint_jacobian!(out, state, path, point)
Compute the Jacobian mapping the Mechanism
's joint velocity vector $v$ to the velocity of a point fixed to the target of the joint path (the body succeeding the last joint in the path) with respect to the source of the joint path (the body preceding the first joint in the path).
Uses state
to compute the transform from the Mechanism
's root frame to the frame in which out
is expressed if necessary.
This method does its computation in place, performing no dynamic memory allocation.
RigidBodyDynamics.point_jacobian
— Methodpoint_jacobian(state, path, point)
Compute the Jacobian mapping the Mechanism
's joint velocity vector $v$ to the velocity of a point fixed to the target of the joint path (the body succeeding the last joint in the path) with respect to the source of the joint path (the body preceding the first joint in the path).
RigidBodyDynamics.subtree_mass
— Methodsubtree_mass(base, mechanism)
Return the mass of a subtree of a Mechanism
, rooted at base
(including the mass of base
).