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

Mechanism

Dojo.MechanismType
Mechanism{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)
source
Dojo.get_nodeFunction
get_node(mechanism, name) 

return Node from Mechanism 

mechanism: Mechanism 
name: unique identifier for node
source
Dojo.get_bodyFunction
get_body(mechanism, name) 

returns Body from Mechanism

mechanism: Mechanism 
name: unique identifier for body
source
Dojo.get_jointFunction
get_joint(mechanism, name) 

return JointConstraint from Mechanism 

mechanism: Mechanism 
name: unique identifier for joint
source
Dojo.get_contactFunction
get_contact(mechanism, name) 

returns ContactConstraint from Mechanism 

mechanism: Mechanism 
name: unique identifier for contact
source
Dojo.get_next_stateFunction
get_next_state(mechanism) 

return the maximal state of mechanism after one simulation step

mechanism: Mechanism
source
Dojo.set_input!Function
set_input(mechanism, u) 

set input for each joint in mechanism 

mechanism: Mechanism 
u: input
source
Dojo.maximal_dimensionFunction
maximal_dimension(mechanism)

dimension of a mechanism's maximal representation

mechanism: Mechanism
source
Dojo.minimal_dimensionFunction
minimal_dimension(mechanism)

dimension of a mechanism's minimal representation

mechanism: Mechanism
source
Dojo.input_dimensionsFunction
input_dimensions(mechanism)

return an array with the input dimensions of all joints

mechanism: Mechanism
source
Dojo.root_to_leaves_orderingFunction
root_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 traversal
source
Dojo.set_floating_baseFunction
set_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 body
source
Dojo.set_external_force!Function
set_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 frame
source
Dojo.add_external_force!Function
add_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 frame
source

Nodes

Dojo.BodyType
Body{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 Body
source
Dojo.OriginType
Origin{T} <: Node{T}

Global reference frame

id: always 0 
name: always :origin 
state: State; defaults to zero values
shape: Shape; defaults to EmptyShape
source
Dojo.ShapeType
Shape{T} 

Abstract type; Subtypes contain geometric and visual information for a Body.
source
Dojo.MeshType
Mesh{T} <: Shape{T}

Contains geometric and visual information based on .obj file
source
Dojo.BoxType
Box{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: RGBA
source
Dojo.CylinderType
Cylinder{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: RGBA
source
Dojo.CapsuleFunction
Capsule 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: RGBA
source
Dojo.SphereType
Sphere{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: RGBA
source
Dojo.PyramidType
Pyramid{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: RGBA
source
Dojo.FrameShapeType
FrameShape{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 used
source
Dojo.CombinedShapesType

CombinedShapes{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)
source

Joints

Dojo.JointType

Joint{T}

Abstract type for 3-dimensional constraint between two Body objects

source
Dojo.RotationalType
Rotational{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 torque
source
Dojo.TranslationalType
Translational{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 force
source
Dojo.JointConstraintType
JointConstraint{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} objects
source
Dojo.FloatingFunction
Floating{T} <: JointConstraint{T} 

no restricted degrees of freedom between two bodies
source
Dojo.FixedFunction
Fixed{T} <: JointConstraint{T}

fixed connection between two bodies
source
Dojo.PrismaticFunction
Prismatic{T} <: JointConstraint{T}

one translational degree of freedom between two bodies
source
Dojo.PlanarFunction
Planar{T} <: JointConstraint{T} 

two translational degree of freedom between two bodies
source
Dojo.FixedOrientationFunction
FixedOrientation{T} <: JointConstraint{T} 

three translational degree of freedom between two bodies
source
Dojo.RevoluteFunction
Revolute{T} <: JointConstraint{T} 

one rotational degree of freedom between two bodies
source
Dojo.CylindricalFunction
Cylindrical{T} <: JointConstraint{T} 

one translational and one rotational degree of freedom between two bodies
source
Dojo.PlanarAxisFunction
PlanarAxis{T} <: JointConstraint{T} 

two translational and one rotational degree of freedom between two bodies
source
Dojo.FreeRevoluteFunction
FreeRevolute{T} <: JointConstraint{T} 

free translation with rotation along one axis
source
Dojo.OrbitalFunction
Orbital{T} <: JointConstraint{T} 

two rotational degrees of freedom between two bodies
source
Dojo.PrismaticOrbitalFunction
PrismaticOrbital{T} <: JointConstraint{T} 

one translational and two rotational degrees of freedom between two bodies
source
Dojo.PlanarOrbitalFunction
PlanarOrbital{T} <: JointConstraint{T} 

two translational and two rotational degrees of freedom between two bodies
source
Dojo.FreeOrbitalFunction
FreeOrbital{T} <: JointConstraint{T} 

three translational and two rotational degrees of freedom between two bodies
source
Dojo.SphericalFunction
Spherical{T} <: JointConstraint{T} 

three rotational degrees of freedom between two bodies
source
Dojo.CylindricalFreeFunction
CylindricalFree{T} <: JointConstraint{T} 

one translational and three rotational degrees of freedom between two bodies
source
Dojo.PlanarFreeFunction
PlanarFree{T} <: JointConstraint{T} 

two translational and three rotational degrees of freedom between two bodies
source

Contacts

Dojo.ContactType
Contact{T,N} 

Abstract type containing contact information associated with Body objects.
source
Dojo.ImpactContactType
ImpactContact{T,N} <: Contact{T,N}

contact object for impact (i.e., no friction)

collision: Collision
source
Dojo.LinearContactType
LinearContact{T,N} <: Contact{T,N}

contact object for impact and friction with a linearized friction cone

friction_coefficient: value of friction coefficient
collision: Collision
source
Dojo.NonlinearContactType
NonlinearContact{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 contact
source
Dojo.ContactConstraintType
ContactConstraint{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 behaviors
source
Dojo.contact_constraintFunction
contact_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, :impact
source
Dojo.contact_locationFunction
contact_location(contact, x, q)

location of contact point in world coordinates

contact: ContactConstraint
x: body position
q: body orientation
source
Dojo.get_sdfFunction
get_sdf(contact, x, q)

returns the signed distance for a contact

contact: ContactConstraint
x: body position
q: body orientation
source
Dojo.SphereHalfSpaceCollisionType
SphereHalfSpaceCollision 

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 contact
source
Dojo.SphereSphereCollisionType
SphereSphereCollision 

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 body
source
Dojo.SphereCapsuleCollisionType
SphereCapsuleCollision 

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 contact
source
Dojo.SphereBoxCollisionType
SphereBoxCollision 

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 contact
source
Dojo.contact_normalFunction
contact_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 orientation
source
Dojo.contact_tangentFunction
contact_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 orientation
source

Representations

Dojo.StateType
State{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 dynamics
source
Dojo.minimal_to_maximalFunction
minimal_to_maximal(mechanism, y)

convert minimal to maximal representation

mechanism: Mechanism
y: minimal state
source
Dojo.maximal_to_minimalFunction
maximal_to_minimal(mechanism, z)

convert maximal to minimal representation

mechanism: Mechanism
z: maximal state
source

Mechanics

Dojo.mechanical_energyFunction
mechanical_energy(mechanism, storage)

mechanism's total mechanical energy

mechanism: Mechanism 
storage: Storage
source
Dojo.kinetic_energyFunction
kinetic_energy(mechanism, storage)

mechanism's kinetic energy from linear and angular velocity

mechanism: Mechanism 
storage: Storage
source
Dojo.potential_energyFunction
potential_energy(mechanism, storage)

mechanism's potential energy from gravity and springs

mechanism: Mechanism 
storage: Storage
source
Dojo.momentumFunction
momentum(mechanism, storage)

mechanism's linear and angular momentum

mechanism: Mechanism
storage: Storage
source

Simulate

Dojo.StorageType
Storage{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 velocity
source
Dojo.step!Function
step!(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: SolverOptions
source
Dojo.step_minimal_coordinates!Function
step_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: SolverOptions
source
Dojo.simulate!Function
simulate!(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: SolverOptions
source

Gradients

Dojo.get_maximal_gradients!Function
get_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: SolverOptions
source
Dojo.get_minimal_gradients!Function
get_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: SolverOptions
source

Solver

Dojo.SolverOptionsType
SolverOptions{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 false
source
Dojo.mehrotra!Function
mehrotra!(mechanism; opts)

interior-point solver for simulation-step feasibility problem

mechanism: Mechanism
opts: SolverOptions
source

Visualization

Dojo.visualizeFunction
visualize(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 mechanism
source
Dojo.build_robotFunction
build_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: RGBA
source
Dojo.set_camera!Function
set_camera!(vis; zoom, cam_pos)

position and zoom for camera in visualization

vis: Visualizer
zoom: value for zoom
cam_pos: position of camera
source
Dojo.set_light!Function
set_light!(vis; ambient, fill, pointX, pointXshadow, direction)

lighting conditions for visualization

vis: Visualizer
ambient: value for ambient lighting
direction: positive or negative direction for light
source
Dojo.set_surface!Function
set_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 domain
source
Dojo.set_floor!Function
set_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 grid
source
Dojo.set_arrow!Function
set_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
source