| Interface | Description |
|---|---|
| AttachingComponent |
A model component associated with a dynamic attachment which can be used as
an attachment request.
|
| BodyConstrainer |
Subclass of Constrainer that applies constraints to rigid bodies and frames
and implements versions of
addBilateralConstraints and addUnilateralConstraints that permit block indices to be reassigned
via a solve index map. |
| Collidable |
Indicates a model component that can collide with other Collidables.
|
| CollidableBody |
Indicates a Collidable that is capable of actual collision handling.
|
| CollidableDynamicComponent |
Describes a DynamicComponent that can response to collisions.
|
| ConditionalPoint |
Describes a point, usually belonging to a MultiPointSpring, which is only
active for particular model configugration.
|
| ConnectableBody |
Defines a component to which joints can be attached.
|
| Constrainer |
Implements a constraint acting on one or more dynamic compnents.
|
| ContactMaster |
Adds blocks to constraint matrices to implement the constraint conditions
requires for contact, including both normal and frictional contact
conditions.
|
| DynamicAgent | |
| DynamicAttachment |
Object that implements attachment between dynamic components.
|
| DynamicAttachmentComp |
A ModelComponent that is also a DynamicAttachment
|
| DynamicComponent | |
| ExcitationComponent |
Defines an object that can emit and recieve muscle control excitations.
|
| ForceComponent |
A ModelComponent that implements ForceEffector
|
| ForceEffector |
An object that exerts forces within a mechanical model.
|
| ForceTargetComponent |
Indicates a force effector whose force can be controlled by the the inverse
controller.
|
| FrameAttachable |
Defines a component to which a frame can be attached.
|
| HasAttachments |
Indicates a model component that contains one or more DynamicAttachments
internally, as either child or internal (hidden) components.
|
| HasDistanceGrid |
Methods exported by components which support a signed distance grid.
|
| HasSlaveObjects |
Indicates a model component that contains objects (not necessarily just
ModelComponents) whose position and/or velocity are completely coupled to
the position and velocity of the dynamic components of the system.
|
| HasSurfaceMesh |
Defines components that are associated with surface meshes.
|
| IsMarkable |
Can add a marker to this component
|
| MechSystem |
Interface to a second order mechanical system that can be integrated by
a variety of integrators.
|
| MechSystemModel | |
| MotionTargetComponent |
Indicates a dynamic component for which motion targets can be set.
|
| MovingMarker |
Describes a marker point whose location with respect to its master
components varies with the model configration.
|
| MuscleComponent |
Composite interface describing force effectors that are also renderable
components and admit excitation.
|
| PlanarComponent |
Indicates a component that is constrained to a plane
|
| PointAttachable |
Defines a component to which a point can be attached.
|
| RequiresInitialize |
Indicates a component, other than a MechSystemModel, that requires
initialization when its containing model is initialized.
|
| RequiresPrePostAdvance |
Indicates a component, other than a MechSystemModel, that requires
processing before and/or after its containing
model is advanced.
|
| SolveMatrixModifier |
Class that modifiers a solve or stiffness matrix and associated force vector.
|
| WrapComponent |
A ModelComponent that implements Wrappable
|
| Wrappable |
| Class | Description |
|---|---|
| AttachedPoint | |
| AxialSpring | |
| AxialSpringList<S extends AxialSpring> | |
| AxialSpringTest | |
| BeamBody | |
| BodyConnector |
Base class for implementing constraints between two connectable bodies, or
between a single connectable body and ground.
|
| BodyConnectorTest | |
| Collidable.Group |
Special Collidable subclass used to denote generic groups of
Collidables.
|
| CollidablePair |
Describes a pair of Collidable model components.
|
| CollisionBehavior |
Contains information describing the appropriate collision response
between two bodies.
|
| CollisionBehaviorList | |
| CollisionComponent |
Base class for both CollisionBehavior and CollisionResponse objects.
|
| CollisionHandler |
Class that generates the contact constraints between a specific
pair of collidable bodies.
|
| CollisionHandlerTable |
Structure to store ColllisionHandlers within a CollisionManager.
|
| CollisionHandlerTableTest |
Unit tester for CollisionHandlerTable
|
| CollisionManager |
A special component that manages collisions between collidable bodies on
behalf of a MechModel.
|
| CollisionManagerTest |
Test jig for the CollisionManager.
|
| CollisionRenderer |
Class to perform rendering for a CollisionHandler
|
| CollisionResponse |
Collects the collision response characteristics for a specific pair of
collidables.
|
| CollisionResponseList | |
| ConstrainerBase | |
| ContactConstraint |
Information for a contact constraint formed by a single contact point.
|
| ContactData |
Information about a single contact constraint that is needed for later
processing, either in a collision response or for rendering.
|
| CylindricalJoint |
Implements a 2 DOF cylindrical joint, in which frame C rotates
clockwise about the z axis of frame D by an angle
theta, and
also translates along the z axis of D by a distance z. |
| DeformableBody | |
| DistanceGridComp |
Component that encapsulates a DistanceGrid.
|
| DualQuaternionDeriv |
Utility methods for computing derivatives assocaited with dual quaternions.
|
| DualQuaternionDerivTest | |
| DynamicAttachmentBase |
Component that implements attachment between dynamic components.
|
| DynamicAttachmentTestBase<C extends DynamicAttachment> | |
| DynamicAttachmentWorker |
Worker class that applies DynamicAttachments to reduce a dynamic system.
|
| DynamicComponentBase | |
| DynamicMeshComponent |
Mesh component that is driven by dynamics
|
| EBBeamBody | |
| EBBeamBodyTest | |
| EllipsoidJoint |
Implements a 4 DOF joint, in which the origin of frame C is constrained to
lie on the surface of an ellipsoid in frame D, while being free to rotate
about the axis normal to the ellipsoid surface and a second axis in the
surface tangent plane.
|
| EllipsoidJoint3d |
Implements a 3 DOF joint, in which the origin of frame C is constrained to lie
on the surface of an ellipsoid in frame D, while being free to rotate about the
axis normal to the ellipsoid surface.
|
| ExcitationSource |
A container class comprising both an excitation component and a gain value.
|
| ExcitationSourceList | |
| ExcitationUtils |
Support routines for Muscle excitations.
|
| FixedAxisJoint |
Experimental 5 DOF joint in which rotation is restricted to 2 DOF.
|
| FixedMeshBody | |
| ForceEffectorList | |
| Frame | |
| FrameAttachment | |
| FrameBlock | |
| FrameFrameAttachment |
Class to attach a frame to another frame.
|
| FrameMarker | |
| FrameSpring | |
| FrameSpringTest | |
| FrameState | |
| FrameTarget |
Contains motion target information for a point.
|
| FrameTargetTest |
Contains motion target information for a point.
|
| FreeJoint |
Implements a six DOF coupling that allows complete motion in space, but with
translational and rotational limits.
|
| GenericMarker | |
| GimbalJoint |
Implements a 3 DOF spherical joint parameterized by roll-pitch-yaw
angles.
|
| HingeJoint |
Implements a 1 DOF revolute joint, in which frame C rotates
counter-clockwise about the z axis of frame D by an angle
theta. |
| JointBase |
Subclass of BodyConnector that provides support for coordinates.
|
| JointBasedMovingMarker |
Special frame marker that updates its location (with respect to the frame)
as a function of joint coordinates.
|
| JointConditionalMarker |
Special frame marker that is conditional upon being within a certain joint
coordinate range.
|
| JointCoordinateCoupling | |
| JointCoordinateHandle |
Handle for accessing values and operations specific to a joint coordinate.
|
| JointLimitForce |
Applies a restoring force to a joint coordinate when its value falls outside
a specfied range.
|
| LinearPointConstraint |
Constrain a linear combination of points to sum to a value:
sum( w_i p_i, i=0..N ) = pos
Useful for "attaching" an arbitrary position inside one finite element
to another arbitrary position inside a different element, or to a
specific point in space
|
| Marker | |
| MechModel | |
| MechModelState | |
| MechSystem.ConstraintInfo |
Contains information for a single constraint direction
|
| MechSystemBase | |
| MechSystemSolver |
Implements implicit integration for MechSystem
|
| MeshComponent |
Contains information about a mesh, including the mesh itself, and it's
possible file name and transformation with respect to the original file
definition.
|
| MeshComponentList<P extends MeshComponent> | |
| MeshInfo |
Contains information about a mesh, including the mesh itself, and it's
possible file name and transformation with respect to the original file
definition.
|
| MotionTarget |
Contains motion target information for a point.
|
| MultiPointMuscle | |
| MultiPointMuscleVia | |
| MultiPointSpring |
Multi-segment point-based spring that supports supports wrapping of selected
segments.
|
| MultiPointSpring.SegmentSpec |
Stores specification information for the segments of this spring.
|
| MultiPointSpringList<S extends MultiPointSpring> | |
| MultiPointSpringTest | |
| Muscle | |
| MuscleExciter | |
| NodalFrameTest | |
| Particle | |
| ParticleConstraintBase |
NOTE: This class is still under construction.
|
| ParticleLineConstraint | |
| ParticleMeshConstraint |
NOTE: This class is still under construction.
|
| ParticlePlaneConstraint | |
| PlanarConnector |
Implements a 5 DOF connector in which the origin of C is constrained
to lie on the x-y plane of D, and C is otherwise free to rotate.
|
| PlanarJoint |
Implements a 3 DOF planer joint, in which the origin of frame C is
constrained to lie in the x-y plane of frame D, while being free to rotate
about D's z axis.
|
| PlanarPoint |
A 3-dimensional point that is confined to a plane.
|
| PlanarProjection |
Utility methods for transforming between matrices from world to planar
coordinates.
|
| PlanarTranslationJoint |
Implements a 2 DOF planer joint, in which the origin of frame C is
constrained to lie in the x-y plane of frame D and rotation is not
permitted.
|
| Point | |
| PointAttachment | |
| PointForce | |
| PointFrameAttachment | |
| PointFrameAttachmentTest | |
| PointList<P extends Point> | |
| PointMeshForce |
An experimental component that generates forces between a set of points and
collision with a mesh specified by a mesh contained within a
MeshComponent. |
| PointParticleAttachment | |
| PointParticleAttachmentTest | |
| PointPlaneForce | |
| PointSpringBase |
Base class for springs based on two or more points
|
| PointSpringList<S extends PointSpringBase> | |
| PointState | |
| PointTarget |
Contains motion target information for a point.
|
| PointTargetTest |
Contains motion target information for a point.
|
| RenderableConstrainerBase | |
| RevoluteJoint |
Legacy class that implements a 1 DOF revolute joint, in which frame C
rotates about the z axis of frame D.
|
| RigidBody | |
| RigidBodySolver |
Solves a sub-set of a MechSystem defined by rigid bodies
|
| RigidBodyTest | |
| RigidCompositeBody | Deprecated
the functionality offered is now provided by
RigidBody. |
| RigidCylinder | |
| RigidEllipsoid | |
| RigidMesh | |
| RigidMeshComp | |
| RigidSphere | |
| RigidTorus | |
| RollPitchJoint |
Legacy class that implements a 2 DOF roll-pitch joint, which allows frame C
to rotate with respect to frame D.
|
| SegmentedPlanarConnector |
Implements a 5 DOF connector in which the origin of C is constrained to lie
on a piecewise linear surface defined by a piecewise linear curve in the x-z
plane of D.
|
| SkewedUniversalJoint |
Implements a skewed 2 DOF roll-pitch joint, in which the roll and pitch
joints are skewed with respect to each other by an angle
skewAngle,
such that the angle between them is PI/2 - skewAngle. |
| SkinMeshBase |
Base class for a SkinMeshBody, which is a type of mesh component in which each
vertex is attached to one or more underlying dynamic master components using
a
PointAttachment. |
| SliderJoint |
Implements a 1 DOF prismatic joint, in which frame C translates along the z
axis of frame D by a distance
z. |
| SlottedHingeJoint |
Implements a 2 DOF ``slotted revolute'' joint, in which frame C rotates
clockwise about the z axis of frame D by an angle
theta, and
also translates along the x axis of D by a distance x. |
| SoftPlaneCollider | |
| SolidJoint |
Auxiliary class used to solve constrained rigid body problems.
|
| SolveMatrixTest | |
| SphericalJoint |
Implements a 3 DOF spherical joint in which frames C and D share an origin
and C is free to assume any orientation with respect to D.
|
| SphericalJointBase |
Auxiliary class used to solve constrained rigid body problems.
|
| SphericalRpyJoint |
Legacy class that implements a 3 DOF spherical joint parameterized by
roll-pitch-yaw angles.
|
| Spring | |
| StaticRigidBodySolver |
Base for classes that perform static constraint-based solves on a set of
rigid bodies contained within a MechModel.
|
| StiffnessMatrixScaler |
Class that applies both mass and length scaling to a stiffness matrix.
|
| UniversalJoint |
Implements a 2 DOF rotary joint, which allows frame C to rotate with respect
to frame D by a rotation
roll about the z axis, followed by a
rotation pitch about the rotated y axis. |
| VertexContactMaster |
Implements a ContactMaster that combines the weighted contact
masters for a single vertex-based contact
|
| YPRStiffnessTest | |
| YPRStiffnessUtils |
Methods to support the computation of stiffness matrices where the
orientation derivatives for Frames are represented with respect to
yaw-pitch-roll instead of angular displacement.
|
| Enum | Description |
|---|---|
| Collidable.Collidability |
Indicates the collision types that are enabled for this Collidable.
|
| CollisionBehavior.ColorMapType |
Specified what type of data should be used when drawing a color
map over the collision area.
|
| CollisionBehavior.Method |
Specifies the contact method defining how the constraints are
generated for handling collisions.
|
| CollisionBehavior.VertexPenetrations |
Indicates when two-way contact is used for the
CollisionBehavior.Method.VERTEX_PENETRATION or CollisionBehavior.Method.VERTEX_EDGE_PENETRATION
contact methods. |
| CollisionManager.ColliderType |
Specifies the collider that generates contact information between the
two meshes.
|
| ContactConstraint.StictionState |
Describes the static friction state of this contact.
|
| DistanceGridComp.SurfaceType |
Specfies the type of interpolation that should be used when constructing
an iso-surface for the grid.
|
| ExcitationComponent.CombinationRule |
Combination rules for excitations.
|
| GimbalJoint.AxisSet |
Specifies whether the roll-pitch-yaw angles of this joint describe
instrinic rotations about the Z-Y-X or X-Y-Z axes.
|
| MechSystemSolver.Integrator | |
| MechSystemSolver.PosStabilization |
Indicates the method by which positions should be stabilized.
|
| MotionTarget.TargetActivity | |
| PointMeshForce.ForceType |
Determines force on the mesh-interacting points are computed in response
to the point's distance from the mesh
|
| PointPlaneForce.ForceType | |
| RigidBody.InertiaMethod | |
| UniversalJoint.AxisSet |
Specifies whether the roll-pitch-yaw angles of this joint describe
instrinic rotations about the Z-Y-X or X-Y-Z axes.
|