Mechanisms
Index
RigidBodyDynamics.Mechanism
RigidBodyDynamics.Mechanism
RigidBodyDynamics.attach!
RigidBodyDynamics.attach!
RigidBodyDynamics.bodies
RigidBodyDynamics.body_fixed_frame_definition
RigidBodyDynamics.body_fixed_frame_to_body
RigidBodyDynamics.fixed_transform
RigidBodyDynamics.in_joints
RigidBodyDynamics.joint_to_parent
RigidBodyDynamics.joints
RigidBodyDynamics.joints_to_children
RigidBodyDynamics.maximal_coordinates
RigidBodyDynamics.non_tree_joints
RigidBodyDynamics.num_additional_states
RigidBodyDynamics.num_constraints
RigidBodyDynamics.num_positions
RigidBodyDynamics.num_velocities
RigidBodyDynamics.out_joints
RigidBodyDynamics.path
RigidBodyDynamics.predecessor
RigidBodyDynamics.rand_chain_mechanism
RigidBodyDynamics.rand_floating_tree_mechanism
RigidBodyDynamics.rand_tree_mechanism
RigidBodyDynamics.rand_tree_mechanism
RigidBodyDynamics.rebuild_spanning_tree!
RigidBodyDynamics.remove_fixed_tree_joints!
RigidBodyDynamics.remove_joint!
RigidBodyDynamics.root_body
RigidBodyDynamics.root_frame
RigidBodyDynamics.submechanism
RigidBodyDynamics.successor
RigidBodyDynamics.tree_joints
The Mechanism
type
RigidBodyDynamics.Mechanism
— Type.mutable struct Mechanism{T}
A Mechanism
represents an interconnection of rigid bodies and joints. Mechanism
s store the joint layout and inertia parameters, but no state-dependent information.
Creating and modifying Mechanism
s
See also URDF parsing and writing for URDF file format support.
RigidBodyDynamics.Mechanism
— Method.Create a new Mechanism
containing only a root body, to which other bodies can be attached with joints.
RigidBodyDynamics.attach!
— Method.attach!(mechanism, parentbody, childmechanism; child_root_pose)
Attach a copy of childmechanism
to mechanism
. Return mappings from the bodies and joints of the childmechanism
to the bodies and joints that were added to mechanism
.
Essentially replaces the root body of a copy of childmechanism
with parentbody
(which belongs to mechanism
).
Note: gravitational acceleration for childmechanism
is ignored.
RigidBodyDynamics.attach!
— Method.attach!(mechanism, predecessor, successor, joint; joint_pose, successor_pose)
Attach successor
to predecessor
using joint
.
See Joint
for definitions of the terms successor and predecessor.
The Transform3D
s joint_pose
and successor_pose
define where joint
is attached to each body. joint_pose
should define frame_before(joint)
with respect to any frame fixed to predecessor
, and likewise successor_pose
should define any frame fixed to successor
with respect to frame_after(joint)
.
predecessor
is required to already be among the bodies of the Mechanism
.
If successor
is not yet a part of the Mechanism
, it will be added to the Mechanism
. Otherwise, the joint
will be treated as a non-tree edge in the Mechanism
, effectively creating a loop constraint that will be enforced using Lagrange multipliers (as opposed to using recursive algorithms).
RigidBodyDynamics.maximal_coordinates
— Method.maximal_coordinates(mechanism)
Return a dynamically equivalent Mechanism
, but with a flat tree structure with all bodies attached to the root body with a quaternion floating joint, and with the 'tree edge' joints of the input Mechanism
transformed into non-tree edge joints (a constraint enforced using Lagrange multipliers in dynamics!
). In addition, return:
- a mapping from bodies in the maximal-coordinate
Mechanism
to their floating joints. - a mapping from bodies in the input
Mechanism
to bodies in the returnedMechanism
- a mapping from joints in the input
Mechanism
to joints in the returnedMechanism
RigidBodyDynamics.rand_chain_mechanism
— Method.Create a random chain Mechanism
with the given joint types.
Create a random tree Mechanism
, with a quaternion floating joint as the first joint (between the root body and the first non-root body).
RigidBodyDynamics.rand_tree_mechanism
— Method.rand_tree_mechanism(?, parentselector, jointtypes)
Create a random tree Mechanism
with the given joint types. Each new body is attached to a parent selected using the parentselector
function.
RigidBodyDynamics.rand_tree_mechanism
— Method.rand_tree_mechanism(?, jointtypes)
Create a random tree Mechanism
.
remove_fixed_tree_joints!(mechanism)
Remove any fixed joints present as tree edges in mechanism
by merging the rigid bodies that these fixed joints join together into bodies with equivalent inertial properties. Return the fixed joints that were removed.
RigidBodyDynamics.remove_joint!
— Method.remove_joint!(mechanism, joint; flipped_joint_map, spanning_tree_next_edge)
Remove a joint from the mechanism. Rebuilds the spanning tree if the joint is part of the current spanning tree.
Optionally, the flipped_joint_map
keyword argument can be used to pass in an associative container that will be populated with a mapping from original joints to flipped joints, if removing joint
requires rebuilding the spanning tree of mechanism
and the polarity of some joints needed to be changed in the process.
Also optionally, spanning_tree_next_edge
can be used to select which joints should become part of the new spanning tree, if rebuilding the spanning tree is required.
RigidBodyDynamics.submechanism
— Method.submechanism(mechanism, submechanismroot)
Create a new Mechanism
from the subtree of mechanism
rooted at submechanismroot
.
Also return mappings from the bodies and joints of the input mechanism to the bodies and joints of the submechanism.
Any non-tree joint in mechanism
will appear in the returned Mechanism
if and only if both its successor and its predecessor are part of the subtree.
RigidBodyDynamics.rebuild_spanning_tree!
— Method.rebuild_spanning_tree!(mechanism)
rebuild_spanning_tree!(mechanism, flipped_joint_map; next_edge)
Reconstruct the mechanism's spanning tree.
Optionally, the flipped_joint_map
keyword argument can be used to pass in an associative container that will be populated with a mapping from original joints to flipped joints, if the rebuilding process required the polarity of some joints to be flipped.
Also optionally, next_edge
can be used to select which joints should become part of the new spanning tree.
Basic functionality
RigidBodyDynamics.bodies
— Method.bodies(mechanism)
Return the RigidBody
s that are part of the Mechanism
as an iterable collection.
body_fixed_frame_to_body(mechanism, frame)
Return the RigidBody
to which frame
is attached.
Note: this function is linear in the number of bodies and is not meant to be called in tight loops.
RigidBodyDynamics.fixed_transform
— Method.fixed_transform(mechanism, from, to)
Return the transform from CartesianFrame3D
from
to to
, both of which are rigidly attached to the same RigidBody
.
Note: this function is linear in the number of bodies and is not meant to be called in tight loops.
RigidBodyDynamics.in_joints
— Method.in_joints(body, mechanism)
Return the joints that have body
as their successor
.
RigidBodyDynamics.joint_to_parent
— Method.joint_to_parent(body, mechanism)
Return the joint that is part of the mechanism's kinematic tree and has body
as its successor.
RigidBodyDynamics.joints
— Method.joints(mechanism)
Return the Joint
s that are part of the Mechanism
as an iterable collection.
RigidBodyDynamics.joints_to_children
— Method.joints_to_children(body, mechanism)
Return the joints that are part of the mechanism's kinematic tree and have body
as their predecessor.
RigidBodyDynamics.num_additional_states
— Method.num_additional_states(mechanism)
Return the dimension of the vector of additional states $s$ (used for stateful contact models).
RigidBodyDynamics.num_constraints
— Method.num_constraints(mechanism)
Return the number of constraints imposed by the mechanism's non-tree joints (i.e., the number of rows of the constraint Jacobian).
RigidBodyDynamics.num_positions
— Method.num_positions(mechanism)
Return the dimension of the joint configuration vector $q$.
RigidBodyDynamics.num_velocities
— Method.num_velocities(mechanism)
Return the dimension of the joint velocity vector $v$.
RigidBodyDynamics.out_joints
— Method.out_joints(body, mechanism)
Return the joints that have body
as their predecessor
.
RigidBodyDynamics.path
— Method.path(mechanism, from, to)
Return the path from rigid body from
to to
along edges of the Mechanism
's kinematic tree.
RigidBodyDynamics.predecessor
— Method.predecessor(joint, mechanism)
Return the body 'before' the joint, i.e. the 'tail' of the joint interpreted as an arrow in the Mechanism
's kinematic graph.
See Joint
.
RigidBodyDynamics.root_body
— Method.root_body(mechanism)
Return the root (stationary 'world') body of the Mechanism
.
RigidBodyDynamics.root_frame
— Method.root_frame(mechanism)
Return the default frame of the root body.
RigidBodyDynamics.successor
— Method.successor(joint, mechanism)
Return the body 'after' the joint, i.e. the 'head' of the joint interpreted as an arrow in the Mechanism
's kinematic graph.
See Joint
.
RigidBodyDynamics.tree_joints
— Method.tree_joints(mechanism)
Return the Joint
s that are part of the Mechanism
's spanning tree as an iterable collection.
body_fixed_frame_definition(mechanism, frame)
Return the definition of body-fixed frame frame
, i.e., the Transform3D
from frame
to the default frame of the body to which it is attached.
Note: this function is linear in the number of bodies and is not meant to be called in tight loops.
See also default_frame
, frame_definition
.
RigidBodyDynamics.non_tree_joints
— Method.non_tree_joints(mechanism)
Return the Joint
s that are not part of the Mechanism
's spanning tree as an iterable collection.