API Documentation
Docstrings for Dojo.jl interface members can be accessed through Julia's built-in documentation system or in the list below.
Contents
Index
Dojo.BodyDojo.BoxDojo.CollisionDojo.CombinedShapesDojo.ConstraintDojo.ContactDojo.ContactConstraintDojo.CylinderDojo.EmptyShapeDojo.FrameShapeDojo.ImpactContactDojo.JointDojo.JointConstraintDojo.LinearContactDojo.MechanismDojo.MeshDojo.NodeDojo.NonlinearContactDojo.OriginDojo.PyramidDojo.RotationalDojo.ShapeDojo.SolverOptionsDojo.SphereDojo.SphereBoxCollisionDojo.SphereCapsuleCollisionDojo.SphereHalfSpaceCollisionDojo.SphereSphereCollisionDojo.StateDojo.StorageDojo.TranslationalDojo.CapsuleDojo.CylindricalDojo.CylindricalFreeDojo.FixedDojo.FixedOrientationDojo.FloatingDojo.FreeOrbitalDojo.FreeRevoluteDojo.OrbitalDojo.PlanarDojo.PlanarAxisDojo.PlanarFreeDojo.PlanarOrbitalDojo.PrismaticDojo.PrismaticOrbitalDojo.RevoluteDojo.SphericalDojo.add_external_force!Dojo.build_robotDojo.contact_constraintDojo.contact_locationDojo.contact_normalDojo.contact_tangentDojo.get_bodyDojo.get_contactDojo.get_jointDojo.get_maximal_gradients!Dojo.get_maximal_stateDojo.get_minimal_gradients!Dojo.get_minimal_stateDojo.get_next_stateDojo.get_nodeDojo.get_sdfDojo.input_dimensionDojo.input_dimensionsDojo.kinetic_energyDojo.maximal_dimensionDojo.maximal_to_minimalDojo.maximal_to_minimal_jacobianDojo.mechanical_energyDojo.mehrotra!Dojo.minimal_dimensionDojo.minimal_to_maximalDojo.minimal_to_maximal_jacobianDojo.momentumDojo.potential_energyDojo.root_to_leaves_orderingDojo.set_arrow!Dojo.set_camera!Dojo.set_external_force!Dojo.set_floating_baseDojo.set_floor!Dojo.set_input!Dojo.set_light!Dojo.set_maximal_state!Dojo.set_minimal_state!Dojo.set_surface!Dojo.simulate!Dojo.step!Dojo.step_minimal_coordinates!Dojo.visualizeDojo.zero_coordinates!Dojo.zero_velocities!
Mechanism
Dojo.Mechanism — TypeMechanism{T}
Multi-rigid-body system.
origin: global reference frame represented with Origin
joints: list of JointConstraint objects
bodies: list of Body objects
contacts: list of ContactConstraint objects
system: graph-based representation for mechanism
residual_entries: containt entries for linear system residual
data_matrix: contains parameter information that is fixed during simulation
root_to_leaves: list of node connections traversing from root node to leaves
timestep: time discretization
input_scaling: input scaling for internal use of impulses (default: timestep)
gravity: force vector resulting from gravitational potential
μ: complementarity violation (contact softness)Dojo.get_node — Functionget_node(mechanism, name)
return Node from Mechanism
mechanism: Mechanism
name: unique identifier for nodeDojo.get_body — Functionget_body(mechanism, name)
returns Body from Mechanism
mechanism: Mechanism
name: unique identifier for bodyDojo.get_joint — Functionget_joint(mechanism, name)
return JointConstraint from Mechanism
mechanism: Mechanism
name: unique identifier for jointDojo.get_contact — Functionget_contact(mechanism, name)
returns ContactConstraint from Mechanism
mechanism: Mechanism
name: unique identifier for contactDojo.get_maximal_state — Functionget_maximal_state(mechanism)
return the current maximal state of mechanism
mechanism: MechanismDojo.get_next_state — Functionget_next_state(mechanism)
return the maximal state of mechanism after one simulation step
mechanism: MechanismDojo.get_minimal_state — Functionget_minimal_state(mechanism)
return minimal state for mechanism
mechanism: MechanismDojo.set_maximal_state! — Functionset_maximal_state(mechanism, z)
set the maximal state of a mechanism
mechanism: Mechanism
z: stateDojo.set_minimal_state! — Functionset_minimal_state(mechanism, y)
set the minimal state of a mechanism
mechanism: Mechanism
y: stateDojo.set_input! — Functionset_input(mechanism, u)
set input for each joint in mechanism
mechanism: Mechanism
u: inputDojo.maximal_dimension — Functionmaximal_dimension(mechanism)
dimension of a mechanism's maximal representation
mechanism: MechanismDojo.minimal_dimension — Functionminimal_dimension(mechanism)
dimension of a mechanism's minimal representation
mechanism: MechanismDojo.input_dimension — Functioninput_dimension(mechanism)
return the number of inputs for mechanism
mechanism: MechanismDojo.input_dimensions — Functioninput_dimensions(mechanism)
return an array with the input dimensions of all joints
mechanism: MechanismDojo.zero_coordinates! — Functionzero_coordinates!(mechanism)
set all mechanism body coordinates to zero
mechanism: MechanismDojo.zero_velocities! — Functionzero_velocities!(mechanism)
set all mechanism body velocities to zero
mechanism: MechanismDojo.root_to_leaves_ordering — Functionroot_to_leaves_ordering(mechanism; exclude_origin, exclude_loop_joints)
ordered list of ids from root to leaves, all nodes are visited a single time
excluding: origin, joints forming a loop which are not visited
mechanism: Mechanism
exclude_origin: flag to exclude origin from traversal
exclude_loop_joints: flag to exclude loop joints from traversalDojo.set_floating_base — Functionset_floating_base(mechanism, name)
returns a mechanism with modified joints having body identified with 'name' as the floating base
mechanism: Mechanism
name: Symbol, identifier for floating-base bodyDojo.set_external_force! — Functionset_external_force!(body; force, torque, vertex)
applies an external force on a body
body: Body
force: force in body frame
torque: torque in local frame
vertex: point where force is applied in local frameDojo.add_external_force! — Functionadd_external_force!(body; force, torque, vertex)
adds an additional external force on a body
body: Body
force: force in body frame
torque: torque in local frameNodes
Dojo.Node — TypeNode{T}
Abstract type for graph node objectDojo.Body — TypeBody{T} <: Node{T}
A rigid body object
id: unique identifying number
name: unique identifying name
mass: inertial property (kilograms)
inertia: inertia matrix (kilograms meter^2)
state: State; representation of the system's: position, linear velocity, orientation, and angular velocity
shape: Shape; geometry information about the BodyDojo.Origin — TypeOrigin{T} <: Node{T}
Global reference frame
id: always 0
name: always :origin
state: State; defaults to zero values
shape: Shape; defaults to EmptyShapeDojo.Constraint — TypeConstraint{T}
Abstract type for graph edge objectDojo.Shape — TypeShape{T}
Abstract type; Subtypes contain geometric and visual information for a Body.Dojo.EmptyShape — TypeEmptyShape{T} <: Shape{T}
Contains no geometric or visual informationDojo.Mesh — TypeMesh{T} <: Shape{T}
Contains geometric and visual information based on .obj fileDojo.Box — TypeBox{T} <: Shape{T}
Cuboid geometry
position_offset: geometry origin offset from center of mass
orientation_offset: orientation offset from body frame
xyz: dimensions (meters)
scale: scaling
color: RGBADojo.Cylinder — TypeCylinder{T} <: Shape{T}
cylinder geometry
position_offset: geometry origin offset from center of mass
orientation_offset: orientation offset from body frame
rh: radius and height dimensions (meters)
scale: scaling
color: RGBADojo.Capsule — FunctionCapsule geometry created as a CombinedShapes
position_offset: geometry origin offset from center of mass
orientation_offset: orientation offset from body frame
rh: radius and height dimensions (meters)
scale: scaling
color: RGBADojo.Sphere — TypeSphere{T} <: Shape{T}
sphere geometry
position_offset: geometry origin offset from center of mass
orientation_offset: orientation offset from body frame
r: radius (meters)
scale: scaling
color: RGBADojo.Pyramid — TypePyramid{T} <: Shape{T}
pyramid geometry
position_offset: geometry origin offset from center of mass
orientation_offset: orientation offset from body frame
wh: width and height dimensions (meters)
scale: scaling
color: RGBADojo.FrameShape — TypeFrameShape{T} <: Shape{T}
coordinate frame geometry
position_offset: geometry origin offset from center of mass
orientation_offset: orientation offset from body frame
scale: scaling
color: not usedDojo.CombinedShapes — TypeCombinedShapes{T} <: Shape{T}
composite geometry
position_offset: geometry origin offset from center of mass
orientation_offset: orientation offset from body frame
shape: list of Shape objects
xyz: dimensions (meters)Joints
Dojo.Joint — TypeJoint{T}
Abstract type for 3-dimensional constraint between two Body objects
Dojo.Rotational — TypeRotational{T} <: Joint{T}
constraint limiting rotational degrees of freedom
axis: rotation axis in parent offset frame
axis_mask1: rotation axis mask in pbody's frame
axis_mask2: rotation axis mask in pbody's frame
axis_mask3: rotation axis mask in pbody's frame
orientation_offset: rotation axis offset from pbody's frame
spring :coefficient for joint spring
damper: coefficient for joint damper
spring_offset: nominal joint configuration
joint_limits: lower and upper limits on the joint configuration
spring_type: can be :linear or :sinusoidal (currently not implemented), if linear then we need joint_limits to avoid the 360° singularity.
input: external impulse torqueDojo.Translational — TypeTranslational{T} <: Joint{T}
constraint limiting translational degrees of freedom
axis: translational axis in parent offset frame
axis_mask1: translational axis mask in pbody's frame
axis_mask2: translational axis mask in pbody's frame
axis_mask3: translational axis mask in pbody's frame
vertices: points in parent can child frames
spring: coefficient for joint spring
damper: coefficient for joint damper
spring_offset: nominal joint configuration
joint_limits: lower and upper limits on the joint configuration
spring_type: can be :linear or :sinusoidal (currently not implemented), if linear then we need joint_limits to avoid the 360° singularity.
input: external impulse forceDojo.JointConstraint — TypeJointConstraint{T} <: Constraint{T}
constraint restricting translational and rotational degrees of freedom between two Body objects.
id: a unique identifying number
name: a unique identifying name
translational: Translational
rotational: Rotational
spring: flag for joint springs on
damper: flag for joint dampers on
parent_id: identifying number for parent Body{T}
child_id: identifying number for child Body{T}
minimal_index: indices for minimal coordinates
impulses: joint impulses that maintain constraint between two Body{T} objectsDojo.Floating — FunctionFloating{T} <: JointConstraint{T}
no restricted degrees of freedom between two bodiesDojo.Fixed — FunctionFixed{T} <: JointConstraint{T}
fixed connection between two bodiesDojo.Prismatic — FunctionPrismatic{T} <: JointConstraint{T}
one translational degree of freedom between two bodiesDojo.Planar — FunctionPlanar{T} <: JointConstraint{T}
two translational degree of freedom between two bodiesDojo.FixedOrientation — FunctionFixedOrientation{T} <: JointConstraint{T}
three translational degree of freedom between two bodiesDojo.Revolute — FunctionRevolute{T} <: JointConstraint{T}
one rotational degree of freedom between two bodiesDojo.Cylindrical — FunctionCylindrical{T} <: JointConstraint{T}
one translational and one rotational degree of freedom between two bodiesDojo.PlanarAxis — FunctionPlanarAxis{T} <: JointConstraint{T}
two translational and one rotational degree of freedom between two bodiesDojo.FreeRevolute — FunctionFreeRevolute{T} <: JointConstraint{T}
free translation with rotation along one axisDojo.Orbital — FunctionOrbital{T} <: JointConstraint{T}
two rotational degrees of freedom between two bodiesDojo.PrismaticOrbital — FunctionPrismaticOrbital{T} <: JointConstraint{T}
one translational and two rotational degrees of freedom between two bodiesDojo.PlanarOrbital — FunctionPlanarOrbital{T} <: JointConstraint{T}
two translational and two rotational degrees of freedom between two bodiesDojo.FreeOrbital — FunctionFreeOrbital{T} <: JointConstraint{T}
three translational and two rotational degrees of freedom between two bodiesDojo.Spherical — FunctionSpherical{T} <: JointConstraint{T}
three rotational degrees of freedom between two bodiesDojo.CylindricalFree — FunctionCylindricalFree{T} <: JointConstraint{T}
one translational and three rotational degrees of freedom between two bodiesDojo.PlanarFree — FunctionPlanarFree{T} <: JointConstraint{T}
two translational and three rotational degrees of freedom between two bodiesContacts
Dojo.Contact — TypeContact{T,N}
Abstract type containing contact information associated with Body objects.Dojo.ImpactContact — TypeImpactContact{T,N} <: Contact{T,N}
contact object for impact (i.e., no friction)
collision: CollisionDojo.LinearContact — TypeLinearContact{T,N} <: Contact{T,N}
contact object for impact and friction with a linearized friction cone
friction_coefficient: value of friction coefficient
collision: CollisionDojo.NonlinearContact — TypeNonlinearContact{T,N} <: Contact{T,N}
contact object for impact and friction with a nonlinear friction cone
friction_coefficient: value of friction coefficient
contact_tangent: mapping from world frame to surface tangent frame
contact_normal: inverse/complement of contact_tangent
contact_origin: position of contact on Body relative to center of mass
contact radius: radius of contactDojo.ContactConstraint — TypeContactConstraint{T} <: Constraint{T}
constraint containing information for contact node.
id: unique identifying number
name: unique identifying name
model: type of contact model: ImpactContact, LinearContact, NonlinearContact
parent_id: identifying number of Body experiencing contact
child_id: always 0
impulses: contact impulses applied to Body
impulses_dual: dual contact impulses, used by solver to enforce correct contact behaviorsDojo.contact_constraint — Functioncontact_constraint(bodies::Vector{Body})
generate ContactConstraints for each Body in list
normals: surface normal for each contact point
friction_coefficients: value of coefficient of friction for each contact point (optional for ImpactContact)
contact_origins: the offset with respect to the center of Body for each contact point (optional)
contact_radius: radius for each contact (optional)
contact_type: :nonlinear, :linear, :impactDojo.contact_location — Functioncontact_location(contact, x, q)
location of contact point in world coordinates
contact: ContactConstraint
x: body position
q: body orientationDojo.get_sdf — Functionget_sdf(contact, x, q)
returns the signed distance for a contact
contact: ContactConstraint
x: body position
q: body orientationDojo.Collision — TypeCollision
abstract type defining interaction between two bodiesDojo.SphereHalfSpaceCollision — TypeSphereHalfSpaceCollision
collision between a spherical contact and a flat surface
contact_tangent: mapping from world frame to surface tangent frame
contact_normal: inverse/complement of contact_tangent
contact_origin: position of contact on Body relative to center of mass
contact_radius: radius of contactDojo.SphereSphereCollision — TypeSphereSphereCollision
collision between two spheres
origin_parent: position of contact on parent body relative to center of mass
origin_child: position of contact on parent body relative to center of mass
radius_parent: radius of contact for parent body
radius_child: radius of contact for child bodyDojo.SphereCapsuleCollision — TypeSphereCapsuleCollision
collision between sphere and capsule
origin_sphere: position of sphere contact relative to body center of mass
origin_capsule_a: position of capsule contact a relative to body center of mass
origin_capsule_b: position of capsule contact b relative to body center of mass
radius_sphere: radius of sphere contact
radius_capsule: radius of capsule contactDojo.SphereBoxCollision — TypeSphereBoxCollision
collision between sphere and box
origin_sphere: position of sphere contact relative to body center of mass
origin_box_a: position of box corner contact a relative to body center of mass
origin_box_b: position of box corner contact b relative to body center of mass
radius_sphere: radius of sphere contactDojo.contact_normal — Functioncontact_normal(collision, xp, qp, xc, qc)
the contact normal (from child to parent) between two contact points
collision: Collision
xp: parent body position
qp: parent body orientation
xc: child body position
qc: child body orientationDojo.contact_tangent — Functioncontact_tangent(collision, xp, qp, xc, qc)
contact tangents between two contact points
collision: Collision
xp: parent body position
qp: parent body orientation
xc: child body position
qc: child body orientationRepresentations
Dojo.State — TypeState{T}
state information in maximal coordinates for Body at time steps: 1, 2, 3.
information at time step 3 is recovered using configurations at time step 2 and velocities at time step 2.5.
x1: position at previous time step
q1: orientation (Quaternion) at previous time step
v15: linear velocity at time step 1.5 (midpoint)
ω15: angular velocity at time step 1.5 (midpoint)
x2: position at current time step
q2: orientation (Quaternion) at current time step
JF2: linear impulse (force * time step) applied at current time step
Jτ2: angular impulse (torque * timestep) applied at current time step
Fext: external force applied at current time step
τext: external torque applied at current time step
vsol: linear velocity at time step 2.5 (midpoint); contains current value (index 1) and candidate value (index 2)
ωsol: angular velocity at time step 2.5 (midpoint); contains current value (index 1) and candidate value (index 2)
d: implicit dynamics evaluator (zero vector indicates physics are satisfied)
D: Jacobian of implicit dynamicsDojo.minimal_to_maximal — Functionminimal_to_maximal(mechanism, y)
convert minimal to maximal representation
mechanism: Mechanism
y: minimal stateDojo.maximal_to_minimal — Functionmaximal_to_minimal(mechanism, z)
convert maximal to minimal representation
mechanism: Mechanism
z: maximal stateMechanics
Dojo.mechanical_energy — Functionmechanical_energy(mechanism, storage)
mechanism's total mechanical energy
mechanism: Mechanism
storage: StorageDojo.kinetic_energy — Functionkinetic_energy(mechanism, storage)
mechanism's kinetic energy from linear and angular velocity
mechanism: Mechanism
storage: StorageDojo.potential_energy — Functionpotential_energy(mechanism, storage)
mechanism's potential energy from gravity and springs
mechanism: Mechanism
storage: StorageDojo.momentum — Functionmomentum(mechanism, storage)
mechanism's linear and angular momentum
mechanism: Mechanism
storage: StorageSimulate
Dojo.Storage — TypeStorage{T,N}
contains maximal-representation trajectories
x: position
q: orientation (Quaternion)
v: linear velocity (midpoint)
ω: angular velocity (midpoint)
px: linear momentum
pq: angular momentum
vl: linear velocity
ωl: angular velocityDojo.step! — Functionstep!(mechanism::Mechanism{T}, z::Vector{T}, u::Vector{T}; opts)
simulate mechanism for one time step provided maximal coordinates
mechanism: Mechanism
z: maximal state
u: inputs
opts: SolverOptionsDojo.step_minimal_coordinates! — Functionstep_minimal_coordinates!(mechanism::Mechanism{T}, x::Vector{T}, u::Vector{T}; opts)
simulate mechanism for one time step provided minimal coordinates
mechanism: Mechanism
x: minimal state
u: inputs
opts: SolverOptionsDojo.simulate! — Functionsimulate!(mechanism, steps, storage, control!;
record, verbose, abort_upon_failure, opts)
simulate a mechanism
mechanism: Mechanism
steps: range of steps to simulate
storage: Storage
control!: Function setting inputs for mechanism
record: flag for recording simulation to storage
verbose: flag for printing during simulation
abort_upon_failure: flag for terminating simulation is solver fails to meet tolerances
opts: SolverOptionsGradients
Dojo.get_maximal_gradients! — Functionget_maximal_gradients!(mechanism, z, u; opts)
return maximal gradients for mechanism
note: this requires simulating the mechanism for one time step
mechanism: Mechanism
z: state
u: input
opts: SolverOptionsDojo.get_minimal_gradients! — Functionget_minimal_gradients!(mechanism, y, u; opts)
return minimal gradients for mechanism
note: this requires simulating the mechanism for one time step
mechanism: Mechanism
y: state
u: input
opts: SolverOptionsDojo.maximal_to_minimal_jacobian — Functionmaximal_to_minimal_jacobian(mechanism, z)
Jacobian of mapping from maximal to minimal representation
mechanism: Mechanism
z: maximal stateDojo.minimal_to_maximal_jacobian — Functionminimal_to_maximal_jacobian(mechanism, x)
Jacobian of mapping from minimal to maximal representation
mechanism: Mechanism
y: minimal stateSolver
Dojo.SolverOptions — TypeSolverOptions{T}
Options and tolerances of primal-dual interior point solver.
rtol: tolerance on residual violations (equality constraints); defaults to 1e-6
btol: tolerance on bilinear violations (complementarity constraints); defaults to 1e-4
ls_scale: line search scaling factor (α_new ← ls_scale * α_current); defaults to 0.5
max_iter: maximum number of Newton iterations; defaults to 50
max_ls: maximum number of line search steps; defaults to 10
undercut: complementarity slackness target; solver will aim at reaching complementarity violation = btol / undercut; defaults to Inf
no_progress_max: number of Newton's iterations without progress trigerring the rescaling of the target complementarity violation; defaults to 3
no_progress_undercut: undercut scaling factor (target_new ← target_current / no_progress_undercut); defaults to 10
verbose: flag for printing the status of the solver during the solve; defaults to falseDojo.mehrotra! — Functionmehrotra!(mechanism; opts)
interior-point solver for simulation-step feasibility problem
mechanism: Mechanism
opts: SolverOptionsVisualization
Dojo.visualize — Functionvisualize(mechanism, storage; vis, build, show_contact, animation, color, name)
visualize mechanism using trajectory from storage
mechanism: Mechanism
storage: Storage
vis: Visualizer
build: flag to construct mechanism visuals (only needs to be built once)
show_contact: flag to show contact locations on system
color: RGBA
name: unique identifier for mechanismDojo.build_robot — Functionbuild_robot(mechanism; vis, show_contact, name, color)
construct visuals for mechanism
mechanism: Mechanism
vis: Visualizer
show_contact: flag to show contact locations on mechanism
name: unique identifier
color: RGBADojo.set_camera! — Functionset_camera!(vis; zoom, cam_pos)
position and zoom for camera in visualization
vis: Visualizer
zoom: value for zoom
cam_pos: position of cameraDojo.set_light! — Functionset_light!(vis; ambient, fill, pointX, pointXshadow, direction)
lighting conditions for visualization
vis: Visualizer
ambient: value for ambient lighting
direction: positive or negative direction for lightDojo.set_surface! — Functionset_surface!(vis; f, xlims, ylims, color, n)
adds surface to visualization
vis::Visualizer
f: implicit function representing surface
xlims: lateral domain for surface
ylims: longitudinal domain for surface
color: RGBA
n: number of discretization points along each domainDojo.set_floor! — Functionset_floor!(vis; x, y, z, origin, normal, color, tilepermeter, imagename, axis, grid)
adds floor to visualization
vis::Visualizer
x: lateral position
y: longitudinal position
z: vertical position
origin:: position of the center of the floor
normal:: unit vector indicating the normal to the floor
color: RGBA
tilepermeter: scaling
imagename: path to image
axis: flag to turn on visualizer axis
grid: flag to turn on visualizer gridDojo.set_arrow! — Functionset_arrow!(vis, origin, direction; color, shaft_radius, max_head_radius, scaling, name)
adds an arrow object to scene
vis: Visualizer
origin: point defining arrow base
direction: vector defining arrow
color: RGBA
shaft_radius: dimension of arrow shaft
max_head_radius: dimension of arrow head base
scaling: parameter that scales the entire arrow
name: Symbol