public abstract class DeformableBody extends RigidBody implements PropertyChangeListener
RigidBody.InertiaMethod
Collidable.Collidability, Collidable.Group
CompositeComponent.NavpanelDisplay
Modifier and Type | Field and Description |
---|---|
static PropertyList |
myProps |
DEFAULT_SUBMESHES_SELECTABLE
dynamicVelInWorldCoords, myRenderFrame
enforceUniqueCompositeNames, enforceUniqueNames, myNumber, NULL_OBJ, useCompactPathNames
All, AllBodies, Deformable, Rigid, Self
COPY_REFERENCES, REST_POSITION
TG_ARTICULATED, TG_DRAGGER, TG_PRESERVE_ORIENTATION, TG_SIMULATING
TRANSPARENT, TWO_DIMENSIONAL
Modifier and Type | Method and Description |
---|---|
void |
addDeformedFrameForce(RigidTransform3d A0,
Wrench wr)
Adds to this body's elastic forces the forces arising from applying a
wrench
f on an attached frame. |
void |
addEffectivePointMass(double m,
Vector3d loc)
Adds a point mass to the effective spatial inertia for this Frame.
|
void |
addElasticForce(VectorNd f) |
void |
addExternalElasticForce(VectorNd f) |
int |
addForce(double[] f,
int idx) |
void |
addFrameForce(RigidTransform3d TFL0,
Wrench wr)
Adds to this body's forces the wrench arising from applying a wrench
f on an attached frame. |
void |
addPointForce(Point3d loc,
Vector3d f)
Adds to this body's forces the wrench arising from applying a force
f on an attached point. |
void |
addPointForce(Wrench wr,
VectorNd fe,
Point3d loc,
Vector3d f)
Adds to
wr and fe the wrench and elastic forces
arising from applying a force f on a point loc . |
void |
addPosImpulse(double[] xbuf,
int xidx,
double h,
double[] vbuf,
int vidx) |
void |
addPosJacobian(SparseNumberedBlockMatrix S,
double s)
Scales the components of the position Jacobian associated with this force
effector and adds it to the supplied solve matrix M.
|
void |
addScaledExternalElasticForce(double s,
VectorNd f) |
void |
addSolveBlock(SparseNumberedBlockMatrix S) |
void |
addToPointVelocity(Vector3d vel,
double w,
ContactPoint cpnt)
Computes the velocity imparted to a contact point by this component's
current velocity, multiples it by a weighting factor
w ,
and add it to vel . |
void |
addVelJacobian(SparseNumberedBlockMatrix S,
double s)
Scales the components of the velocity Jacobian associated with this force
effector and adds it to the supplied solve matrix M.
|
void |
applyExternalForces() |
void |
applyForces(double t)
Adds forces to the components affected by this force effector at a
particular time.
|
void |
computeDeformationGradient(Matrix3d F,
Vector3d x0) |
void |
computeDeformedFrame(RigidTransform3d A,
RigidTransform3d A0) |
void |
computeDeformedFrameVel(Twist vel,
RigidTransform3d A0)
Computes the spatial velocity of an attached frame A, as represented in
body coordinates.
|
void |
computeDeformedLocation(Vector3d pos,
Vector3d pos0)
Computes the deformed position in body coordinates
|
void |
computeDeformedVelocity(Vector3d vel,
Vector3d pos0)
Computes the deformed velocity in body coordinates
|
void |
computeElasticJacobian(MatrixNd Pi,
RigidTransform3d A0,
boolean worldCoords)
Compute the transform that maps elastic velocities onto the spatial
velocity of an attached frame A.
|
void |
computeFrameLocation(RigidTransform3d TFL0,
RigidTransform3d TFW) |
void |
computeFramePosition(RigidTransform3d TFW,
RigidTransform3d TFL0) |
void |
computeFrameVelocity(Twist vel,
RigidTransform3d TFL0) |
void |
computePointCoriolis(Vector3d cor,
Vector3d loc)
Computes the velocity derivative of a point attached to this frame
that is due to the current velocity of the frame.
|
void |
computePointLocation(Vector3d loc0,
Vector3d pos)
Computes the location, in body coordinates, of a point whose position
is given in world coordinates.
|
void |
computePointPosition(Vector3d pos,
Point3d loc)
Computes the position, in world coordinates, of a point attached to this
frame.
|
void |
computePointVelocity(Vector3d vel,
Vector3d loc)
Computes the velocity, in world coordinates, of a point attached to this
frame.
|
void |
computeUndeformedFrame(RigidTransform3d A0,
RigidTransform3d A) |
void |
computeUndeformedLocation(Vector3d loc0,
Vector3d loc) |
double |
computeUndeformedLocation(Vector3d pos0,
Vector3d pos,
double tol)
Computes the undeformed position of a given position in body coordinates
|
void |
computeWorldPointForceJacobian(MatrixBlock GT,
Point3d loc)
Computes the force Jacobian, in world coordinates, for a point attached
to this frame.
|
static FemMaterial |
createDefaultMaterial() |
MatrixBlock |
createMassBlock()
Create a matrix block for representing the mass of this component,
initialized to the component's effective mass (instrinsic mass
plus the mass due to all attachmented components).
|
PropertyList |
getAllPropertyInfo()
Returns a list giving static information about all properties exported by
this object.
|
DistanceGridComp |
getDistanceGridComp()
Returns a
DistanceGridComp object that in turn contains
a signed distance grid that can be used with a SignedDistanceCollider,
or null if this Collidable
does not support a signed distance grid (i.e., if
CollidableBody.hasDistanceGrid() returns false ). |
abstract void |
getDShape(Matrix3d Dshp,
int i,
Vector3d pos0) |
void |
getEffectiveMass(Matrix M,
double t)
Gets the effective mass of this component at a particular time.
|
int |
getEffectiveMassForces(VectorNd f,
double t,
int idx)
Gets the mass forces for this component at a particular time.
|
VectorNd |
getElasticForce() |
VectorNd |
getElasticPos() |
double |
getElasticPos(int idx) |
void |
getElasticPos(VectorNd pos) |
VectorNd |
getElasticVel() |
double |
getElasticVel(int idx) |
void |
getElasticVel(VectorNd vel) |
VectorNd |
getExternalElasticForce() |
int |
getForce(double[] f,
int idx) |
boolean |
getFreezeFrame() |
void |
getInverseMass(Matrix Minv,
Matrix M)
Inverts a mass for this component.
|
void |
getMass(Matrix M,
double t)
Gets the mass of this component at a particular time.
|
double |
getMassDamping() |
FemMaterial |
getMaterial() |
int |
getPosDerivative(double[] dxdt,
int idx) |
int |
getPosState(double[] buf,
int idx) |
int |
getPosStateSize() |
abstract void |
getShape(Vector3d shp,
int i,
Vector3d pos0) |
double |
getStiffnessDamping() |
int |
getVelState(double[] buf,
int idx) |
int |
getVelStateSize() |
boolean |
hasDistanceGrid()
Returns
true if this RigidBody supports a signed
distance grid that can be used with a SignedDistanceCollider. |
void |
invalidateStiffness() |
boolean |
isDeformable()
Returns
true if this collidable is deformable. |
int |
mulInverseEffectiveMass(Matrix M,
double[] a,
double[] f,
int idx) |
abstract int |
numElasticCoords() |
void |
propertyChanged(PropertyChangeEvent e) |
void |
setContactConstraint(double[] buf,
double w,
Vector3d dir,
ContactPoint cpnt)
Computes the values for the block matrix which defines this component's
contribution to a contact constraint matrix.
|
void |
setElasticForce(VectorNd f) |
void |
setElasticPos(int idx,
double value) |
void |
setElasticPos(VectorNd pos) |
void |
setElasticVel(int idx,
double value) |
void |
setElasticVel(VectorNd vel) |
void |
setExternalElasticForce(VectorNd f) |
int |
setForce(double[] f,
int idx) |
void |
setFreezeFrame(boolean freeze) |
void |
setMassDamping(double d) |
<T extends FemMaterial> |
setMaterial(T mat) |
int |
setPosState(double[] buf,
int idx)
Replace updatePosState() with updateSlavePosStates() so we don't update
attachments when doing general state uodates.
|
void |
setRandomForce()
Sets the force of this component to a random value.
|
void |
setRandomPosState()
Sets the position state of this component to a random value.
|
void |
setRandomVelState()
Sets the velocity state of this component to a random value.
|
void |
setStiffnessDamping(double d) |
int |
setVelState(double[] buf,
int idx) |
abstract void |
updateStiffnessMatrix() |
void |
zeroExternalForces() |
void |
zeroForces() |
add, addConnector, addEffectiveFrameMass, addMesh, addMesh, addMesh, addMeshComp, addTransformableDependencies, allowCollision, applyGravity, centerPoseOnCenterOfMass, clearMeshComps, collectVertexMasters, componentChanged, containsConnector, containsContactMaster, containsMeshComp, copy, createBox, createBox, createBox, createCylinder, createEllipsoid, createFromMesh, createFromMesh, createFromMesh, createFromMesh, createIcosahedralSphere, createRenderProps, createSphere, extrapolatePose, findComponent, get, get, getByNumber, getCenterOfMass, getCenterOfMass, getCharacteristicRadius, getChildren, getCollidable, getCollidableAncestor, getCollidableIndex, getCollisionMesh, getConnectors, getCopyReferences, getDensity, getDensityRange, getDistanceGrid, getDistanceGridRes, getEffectiveInertia, getEffectiveMass, getEffectiveMassForces, getFrameMarkers, getGridSurfaceRendering, getInertia, getInertialDamping, getInertialDampingMode, getInertiaMethod, getMass, getMass, getMassRange, getMesh, getMeshComp, getMeshComp, getMeshComps, getNavpanelDisplay, getNumberLimit, getRotationalInertia, getRotationalInertia, getSubmeshesSelectable, getSurfaceMesh, getSurfaceMeshComp, getSurfaceMeshes, getVolume, hasChildren, hasForce, hasInvariantMasters, hierarchyContainsReferences, indexOf, isCompound, isDuplicatable, isFreeBody, isMassConstant, mulInverseEffectiveMass, numComponents, numMeshComps, numSurfaceMeshes, penetrationDistance, postscan, prerender, remove, removeConnector, removeMeshComp, removeMeshComp, render, resetEffectiveMass, scaleDistance, scaleMass, scaleSurfaceMesh, scan, setCenterOfMass, setCollidable, setCollidableIndex, setDensity, setDisplayMode, setDistanceGridRes, setDynamic, setGridSurfaceRendering, setInertia, setInertia, setInertia, setInertia, setInertiaFromDensity, setInertiaFromMass, setInertialDamping, setInertialDampingMode, setInertiaMethod, setMass, setMesh, setMesh, setMesh, setPose, setRotationalInertia, setSubmeshesSelectable, setSurfaceMesh, setSurfaceMesh, setSurfaceMesh, subEffectiveInertia, surfaceTangent, transformCoordinateFrame, transformGeometry, translateCoordinateFrame, updateBounds, updateNameMap, write
add1DConstraintBlocks, add2DConstraintBlocks, addExternalForce, addForce, addPointForce, addRelativeVelocity, addScaledExternalForce, addSolveBlocks, addTargetJacobian, collectMasterComponents, computeAppliedWrench, computeForceOnMasters, computeFramePosVel, computePointPosVel, createFrameAttachment, createPointAttachment, getAxisDrawStyle, getAxisLength, getBodyForce, getBodyVelocity, getBodyVelState, getExternalForce, getForce, getForce, getFrameDamping, getFrameDampingMode, getJacobianType, getMoment, getOrientation, getOrientation, getPose, getPose, getPosition, getRenderFrame, getRotaryDamping, getRotaryDampingMode, getRotation, getSelection, getState, getTargetActivity, getTargetOrientation, getTargetPos, getTargetPose, getTargetPosition, getTargetVel, getTargetVelocity, getTraceablePositionProperty, getTraceables, getTransForce, getVelocity, getVelocity, getWorldVelState, resetTargets, setAxisDrawStyle, setAxisLength, setBodyVelocity, setExternalForce, setForce, setFrameDamping, setFrameDampingMode, setOrientation, setPose, setPosition, setRotaryDamping, setRotaryDampingMode, setRotation, setState, setState, setTargetActivity, setTargetOrientation, setTargetPos, setTargetPose, setTargetPosition, setTargetVel, setTargetVelocity, setVelocity, setVelocity, transformPose, updateAttachmentPosStates, velocityLimitExceeded
addAttachmentRequest, addConstrainer, addMasterAttachment, connectToHierarchy, disconnectFromHierarchy, getAttachment, getConstrainers, getMasterAttachments, getSolveIndex, hasState, isActive, isAttached, isControllable, isDynamic, isParametric, removeAttachmentRequest, removeConstrainer, removeMasterAttachment, setAttached, setSolveIndex, transformGeometry
defaultRenderPropsAreNull, getRenderHints, getRenderProps, isSelectable, isVisible, numSelectionQueriesNeeded, setRenderProps, setVisible, updateRenderProps
checkFlag, checkName, checkNameUniqueness, clearFlag, clone, createTempFlag, getGrandParent, getHardReferences, getName, getNameRange, getNavpanelVisibility, getNavpanelVisibility, getNumber, getParent, getProperty, getSoftReferences, isFixed, isMarked, isScanning, isSelected, isWritable, makeValidName, makeValidName, notifyParentOfChange, printReferences, recursivelyContained, recursivelyContains, removeTempFlag, setFixed, setFlag, setMarked, setName, setNavpanelVisibility, setNavpanelVisibility, setNumber, setParent, setScanning, setSelected, setWritable, updateReferences
equals, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
transformPose
createFrameAttachment
createPointAttachment
addAttachmentRequest, removeAttachmentRequest
addConstrainer, addMasterAttachment, getAttachment, getConstrainers, getMasterAttachments, getSolveIndex, isActive, isAttached, isControllable, isDynamic, isParametric, removeConstrainer, removeMasterAttachment, setAttached, setSolveIndex
advanceState, getAuxVarDerivative, getAuxVarState, getStateVersion, hasState, numAuxVars, requiresAdvance, setAuxVarState
transformGeometry, transformPriority
isControllable
public static PropertyList myProps
public void invalidateStiffness()
public PropertyList getAllPropertyInfo()
HasProperties
getAllPropertyInfo
in interface HasProperties
getAllPropertyInfo
in class RigidBody
public abstract int numElasticCoords()
public boolean isDeformable()
Collidable
true
if this collidable is deformable. Whether or
not a collidable is deformable determines how it responds to default
collision behaviors involving deformable and rigid collidables. Also,
self-collisions among sub-collidables of a collidable A are permitted
only if A is deformable.isDeformable
in interface Collidable
isDeformable
in interface ConnectableBody
isDeformable
in class RigidBody
true
if this collidable is deformablepublic boolean hasDistanceGrid()
RigidBody
true
if this RigidBody supports a signed
distance grid that can be used with a SignedDistanceCollider.
The grid itself can be obtained with RigidBody.getDistanceGrid()
.hasDistanceGrid
in interface CollidableBody
hasDistanceGrid
in class RigidBody
true
if a signed distance grid is available
for this RigidBodypublic DistanceGridComp getDistanceGridComp()
RigidBody
DistanceGridComp
object that in turn contains
a signed distance grid that can be used with a SignedDistanceCollider,
or null
if this Collidable
does not support a signed distance grid (i.e., if
CollidableBody.hasDistanceGrid()
returns false
).getDistanceGridComp
in interface CollidableBody
getDistanceGridComp
in class RigidBody
public void setMassDamping(double d)
public double getMassDamping()
public void setStiffnessDamping(double d)
public double getStiffnessDamping()
public static FemMaterial createDefaultMaterial()
public FemMaterial getMaterial()
public <T extends FemMaterial> T setMaterial(T mat)
public boolean getFreezeFrame()
public void setFreezeFrame(boolean freeze)
public void propertyChanged(PropertyChangeEvent e)
propertyChanged
in interface PropertyChangeListener
public VectorNd getElasticPos()
public VectorNd getElasticVel()
public void getElasticPos(VectorNd pos)
public void getElasticVel(VectorNd vel)
public VectorNd getElasticForce()
public void setElasticForce(VectorNd f)
public void addElasticForce(VectorNd f)
public VectorNd getExternalElasticForce()
public void setExternalElasticForce(VectorNd f)
public void addExternalElasticForce(VectorNd f)
public void addScaledExternalElasticForce(double s, VectorNd f)
public void setElasticPos(VectorNd pos)
public void setElasticVel(VectorNd vel)
public MatrixBlock createMassBlock()
DynamicAgent
createMassBlock
in interface DynamicAgent
createMassBlock
in class Frame
public void getMass(Matrix M, double t)
DynamicAgent
getMass
in interface DynamicAgent
getMass
in class RigidBody
M
- matrix to return the mass int
- current timepublic int getEffectiveMassForces(VectorNd f, double t, int idx)
DynamicAgent
f
, starting at the location
specified by idx
. Upon return, this method should
return the value of idx
incremented by the dimension
of the mass forces.getEffectiveMassForces
in interface DynamicAgent
getEffectiveMassForces
in class RigidBody
f
- vector to return the forces int
- current timeidx
- starting location within f
where forces should be storedidx
public void getEffectiveMass(Matrix M, double t)
DynamicAgent
getEffectiveMass
in interface DynamicAgent
getEffectiveMass
in class RigidBody
M
- matrix to return the mass int
- current timepublic int mulInverseEffectiveMass(Matrix M, double[] a, double[] f, int idx)
mulInverseEffectiveMass
in interface DynamicAgent
mulInverseEffectiveMass
in class RigidBody
public void addEffectivePointMass(double m, Vector3d loc)
addEffectivePointMass
in class RigidBody
m
- mass of the pointloc
- location of the point (in local frame coordinates)public void getInverseMass(Matrix Minv, Matrix M)
DynamicAgent
getInverseMass
in interface DynamicAgent
getInverseMass
in class RigidBody
Minv
- matrix to return the inverse mass inM
- matrix containing the mass to be invertedpublic void addSolveBlock(SparseNumberedBlockMatrix S)
addSolveBlock
in interface DynamicAgent
addSolveBlock
in class Frame
public void addPosImpulse(double[] xbuf, int xidx, double h, double[] vbuf, int vidx)
addPosImpulse
in interface DynamicAgent
addPosImpulse
in class Frame
public int getPosDerivative(double[] dxdt, int idx)
getPosDerivative
in interface DynamicAgent
getPosDerivative
in class Frame
public int getPosState(double[] buf, int idx)
getPosState
in interface DynamicAgent
getPosState
in class Frame
public int setPosState(double[] buf, int idx)
RigidBody
setPosState
in interface DynamicAgent
setPosState
in class RigidBody
public int getVelState(double[] buf, int idx)
getVelState
in interface DynamicAgent
getVelState
in class Frame
public int setVelState(double[] buf, int idx)
setVelState
in interface DynamicAgent
setVelState
in class Frame
public int setForce(double[] f, int idx)
setForce
in interface DynamicAgent
setForce
in class Frame
public int addForce(double[] f, int idx)
addForce
in interface DynamicAgent
addForce
in class Frame
public int getForce(double[] f, int idx)
getForce
in interface DynamicAgent
getForce
in class Frame
public int getPosStateSize()
getPosStateSize
in interface DynamicAgent
getPosStateSize
in interface MotionTargetComponent
getPosStateSize
in class Frame
public int getVelStateSize()
getVelStateSize
in interface DynamicAgent
getVelStateSize
in interface MotionTargetComponent
getVelStateSize
in class Frame
public void zeroForces()
zeroForces
in interface DynamicAgent
zeroForces
in class Frame
public void zeroExternalForces()
zeroExternalForces
in interface DynamicAgent
zeroExternalForces
in class Frame
public void applyExternalForces()
applyExternalForces
in interface DynamicAgent
applyExternalForces
in class Frame
public abstract void updateStiffnessMatrix()
public void applyForces(double t)
ForceEffector
applyForces
in interface ForceEffector
applyForces
in class RigidBody
t
- time (seconds)public void addVelJacobian(SparseNumberedBlockMatrix S, double s)
ForceEffector
M is guaranteed to be the same matrix supplied in the most recent call to
addSolveBlocks
, and so implementations may choose
to cache the relevant matrix blocks from that call, instead of retrieving
them directly from M.
addVelJacobian
in interface ForceEffector
addVelJacobian
in class RigidBody
S
- solve matrix to which scaled velocity Jacobian is to be addeds
- scaling factor for velocity Jacobianpublic void addPosJacobian(SparseNumberedBlockMatrix S, double s)
ForceEffector
M is guaranteed to be the same matrix supplied in the most recent call to
addSolveBlocks
, and so implementations may choose
to cache the relevant matrix blocks from that call, instead of retrieving
them directly from M.
addPosJacobian
in interface ForceEffector
addPosJacobian
in class Frame
S
- solve matrix to which scaled position Jacobian is to be addeds
- scaling factor for position Jacobianpublic void computePointPosition(Vector3d pos, Point3d loc)
Frame
computePointPosition
in class Frame
pos
- returns the point positionloc
- position of the point, in body coordinatespublic void computePointLocation(Vector3d loc0, Vector3d pos)
Frame
Frame.computePointPosition(maspack.matrix.Vector3d, maspack.matrix.Point3d)
.computePointLocation
in class Frame
loc0
- returns the point locationpos
- position of the point, in world coordinatespublic void computePointVelocity(Vector3d vel, Vector3d loc)
Frame
computePointVelocity
in class Frame
vel
- returns the point velocityloc
- position of the point, in body coordinatespublic void computePointCoriolis(Vector3d cor, Vector3d loc)
Frame
computePointCoriolis
in class Frame
cor
- returns the point Coriolis term (in world coordinates)loc
- position of the point, in body coordinatespublic void addPointForce(Wrench wr, VectorNd fe, Point3d loc, Vector3d f)
wr
and fe
the wrench and elastic forces
arising from applying a force f
on a point loc
.wr
- accumulates the wrench (world coordinates)fe
- accumulates the elastic forcesloc
- location of the point (undeformed body coordinates)f
- force applied to the point (world coordinates)public void addPointForce(Point3d loc, Vector3d f)
f
on an attached point.addPointForce
in class Frame
loc
- location of the point (body coordinates)f
- force applied to the point (world coordinates)public void addFrameForce(RigidTransform3d TFL0, Wrench wr)
f
on an attached frame.addFrameForce
in class Frame
TFL0
- location of the frame with respect to the bodywr
- 6 DOF force applied to the frame (world coordinates)public void computeWorldPointForceJacobian(MatrixBlock GT, Point3d loc)
Frame
[ I ] [ ] [ [ R loc ] ]where I is the 3x3 identity matrix, R is the frame orientation matrix, and [ x ] denotes the 3x3 skew-symmetric cross product matrix.
GT
- returns the force Jacobianloc
- position of the point, in body coordinatespublic void computeDeformedLocation(Vector3d pos, Vector3d pos0)
public double computeUndeformedLocation(Vector3d pos0, Vector3d pos, double tol)
public void computeDeformedVelocity(Vector3d vel, Vector3d pos0)
public void computeFramePosition(RigidTransform3d TFW, RigidTransform3d TFL0)
computeFramePosition
in class Frame
public void computeFrameLocation(RigidTransform3d TFL0, RigidTransform3d TFW)
computeFrameLocation
in class Frame
public void computeFrameVelocity(Twist vel, RigidTransform3d TFL0)
computeFrameVelocity
in class Frame
public void computeUndeformedFrame(RigidTransform3d A0, RigidTransform3d A)
public void computeDeformedFrame(RigidTransform3d A, RigidTransform3d A0)
public void computeDeformedFrameVel(Twist vel, RigidTransform3d A0)
public void addDeformedFrameForce(RigidTransform3d A0, Wrench wr)
f
on an attached frame.A0
- undeformed location of the frame with respect to the bodywr
- 6 DOF force applied to the frame (body coordinates)public void computeElasticJacobian(MatrixNd Pi, RigidTransform3d A0, boolean worldCoords)
Pi
- stores the elastic JacobianA0
- rest pose of A (relative to the body frame)worldCoords
- if true
, the spatial velocity is rotated
into world coordinates. Otherwise, it is returned in the coordinates of
A.public void setElasticPos(int idx, double value)
public double getElasticPos(int idx)
public void setElasticVel(int idx, double value)
public double getElasticVel(int idx)
public void setContactConstraint(double[] buf, double w, Vector3d dir, ContactPoint cpnt)
CollidableDynamicComponent
n
is the component's velocity state size, and the contact is
defined by a direction dir
and a point cpnt
.
The computed values should be scaled by a weighting factor
w
.setContactConstraint
in interface CollidableDynamicComponent
setContactConstraint
in class Frame
buf
- returns the n values for the block matrixw
- weighting factor by which the values should be scaleddir
- contact direction (world coordinates)cpnt
- contact pointpublic void addToPointVelocity(Vector3d vel, double w, ContactPoint cpnt)
CollidableDynamicComponent
w
,
and add it to vel
.addToPointVelocity
in interface CollidableDynamicComponent
addToPointVelocity
in class Frame
vel
- accumulates contact point velocity (world coordinates)w
- weighting factorcpnt
- contact pointpublic void setRandomPosState()
Frame
setRandomPosState
in interface DynamicAgent
setRandomPosState
in class Frame
public void setRandomVelState()
Frame
setRandomVelState
in interface DynamicAgent
setRandomVelState
in class Frame
public void setRandomForce()
Frame
setRandomForce
in interface DynamicAgent
setRandomForce
in class Frame