Documentation
¶
Overview ¶
Package physics is a 3D physics simulator for creating virtual environments, which can run on the GPU or CPU using GoSL: https://cogentcore.org/lab/gosl See https://cogentcore.org/lab/physics for the main docs.
Index ¶
- Constants
- Variables
- func AddBroadContacts(biA, biB, nci, ncA, ncB int32)
- func AngularAccelAt(di int32, point, axis math32.Vector3) math32.Vector3
- func AngularCorrection(err, derr float32, tfaQ, tfbQ math32.Quat, iInvA, iInvB math32.Matrix3, ...) float32
- func AngularVelocityAt(di int32, point, axis math32.Vector3) math32.Vector3
- func BodyCom(idx int32) math32.Vector3
- func BodyDynamicPos(idx, cni int32) math32.Vector3
- func BodyDynamicQuat(idx, cni int32) math32.Quat
- func BodyHSize(idx int32) math32.Vector3
- func BodyInertia(idx int32) math32.Matrix3
- func BodyInvInertia(idx int32) math32.Matrix3
- func BodyPos(idx int32) math32.Vector3
- func BodyQuat(idx int32) math32.Quat
- func BoxEdge(edgeId int32, upper math32.Vector3, edge0, edge1 *math32.Vector3)
- func BoxSDF(upper, p math32.Vector3) float32
- func BoxSDFGrad(upper, p math32.Vector3) math32.Vector3
- func BoxVertex(ptId int32, upper math32.Vector3) math32.Vector3
- func CapsuleSDF(radius, hh float32, p math32.Vector3) float32
- func ClosestEdgeBox(upper, edgeA, edgeB math32.Vector3, maxIter int32) float32
- func ClosestEdgeCapsule(radius, hh float32, edgeA, edgeB math32.Vector3, maxIter int32) float32
- func ClosestEdgePlane(width, length float32, edgeA, edgeB math32.Vector3, maxIter int32) float32
- func ClosestPointBox(upper, pt math32.Vector3) math32.Vector3
- func ClosestPointLineSegment(a, b, pt math32.Vector3) math32.Vector3
- func ClosestPointPlane(width, length float32, pt math32.Vector3) math32.Vector3
- func ColBoxBox(cpi, maxIter int32, gdA *GeomData, gdB *GeomData, pA, pB, norm *math32.Vector3) float32
- func ColBoxCapsule(cpi, maxIter int32, gdA *GeomData, gdB *GeomData, pA, pB, norm *math32.Vector3) float32
- func ColBoxPlane(cpi, maxIter int32, gdA *GeomData, gdB *GeomData, pA, pB, norm *math32.Vector3) float32
- func ColCapsuleCapsule(cpi, maxIter int32, gdA *GeomData, gdB *GeomData, pA, pB, norm *math32.Vector3) float32
- func ColCapsulePlane(cpi, maxIter int32, gdA *GeomData, gdB *GeomData, pA, pB, norm *math32.Vector3) float32
- func ColCylinderPlane(cpi, maxIter int32, gdA *GeomData, gdB *GeomData, pA, pB, norm *math32.Vector3) float32
- func ColSphereBox(cpi, maxIter int32, gdA *GeomData, gdB *GeomData, pA, pB, norm *math32.Vector3) float32
- func ColSphereCapsule(cpi, maxIter int32, gdA *GeomData, gdB *GeomData, pA, pB, norm *math32.Vector3) float32
- func ColSpherePlane(cpi, maxIter int32, gdA *GeomData, gdB *GeomData, pA, pB, norm *math32.Vector3) float32
- func ColSphereSphere(cpi, maxIter int32, gdA *GeomData, gdB *GeomData, pA, pB, norm *math32.Vector3) float32
- func CollisionBroad(i uint32)
- func CollisionNarrow(i uint32)
- func ConeSDF(radius, hh float32, p math32.Vector3) float32
- func ContactAAngDelta(idx int32) math32.Vector3
- func ContactADelta(idx int32) math32.Vector3
- func ContactAOff(idx int32) math32.Vector3
- func ContactAPoint(idx int32) math32.Vector3
- func ContactBAngDelta(idx int32) math32.Vector3
- func ContactBDelta(idx int32) math32.Vector3
- func ContactBOff(idx int32) math32.Vector3
- func ContactBPoint(idx int32) math32.Vector3
- func ContactConstraint(err float32, q0A, q0B math32.Quat, mInvA, mInvB float32, ...) float32
- func ContactNorm(idx int32) math32.Vector3
- func ContactPoints(dist, margin float32, gdA *GeomData, gdB *GeomData, ...) bool
- func CylinderSDF(radius, hh float32, p math32.Vector3) float32
- func DynamicAcc(idx, cni int32) math32.Vector3
- func DynamicAngAcc(idx, cni int32) math32.Vector3
- func DynamicAngDelta(idx, cni int32) math32.Vector3
- func DynamicAngVel(idx, cni int32) math32.Vector3
- func DynamicBody(idx int32) int32
- func DynamicDelta(idx, cni int32) math32.Vector3
- func DynamicForce(idx, cni int32) math32.Vector3
- func DynamicPos(idx, cni int32) math32.Vector3
- func DynamicQuat(idx, cni int32) math32.Quat
- func DynamicTorque(idx, cni int32) math32.Vector3
- func DynamicVel(idx, cni int32) math32.Vector3
- func DynamicsCurToNext(i uint32)
- func ForcesFromJoints(i uint32)
- func GPUInit()
- func GPURelease()
- func GetBodyDynamic(idx int32) int32
- func GetBodyGroup(idx int32) int32
- func GetBodyWorld(idx int32) int32
- func GetBroadContactA(idx int32) int32
- func GetBroadContactB(idx int32) int32
- func GetBroadContactPointIdx(idx int32) int32
- func GetContactA(idx int32) int32
- func GetContactB(idx int32) int32
- func GetContactPointIdx(idx int32) int32
- func GetJointAngularDoFN(idx int32) int32
- func GetJointEnabled(idx int32) bool
- func GetJointLinearDoFN(idx int32) int32
- func GetJointNoLinearRotation(idx int32) bool
- func GetJointParentFixed(idx int32) bool
- func GetJointTargetPos(idx, dof int32) float32
- func GetJointTargetVel(idx, dof int32) float32
- func GroupsCollide(ga, gb int32) bool
- func InitDynamics(i uint32)
- func InitGeomData(bi int32, gd *GeomData)
- func JointAngLambda(idx int32) math32.Vector3
- func JointAxis(idx, dof int32) math32.Vector3
- func JointAxisDoF(didx int32) math32.Vector3
- func JointAxisLimitsUpdate(dof int32, axis math32.Vector3, lower, upper float32, ...)
- func JointAxisTarget(axis math32.Vector3, targ, weight float32, ...)
- func JointCForce(idx int32) math32.Vector3
- func JointCPos(idx int32) math32.Vector3
- func JointCQuat(idx int32) math32.Quat
- func JointCTorque(idx int32) math32.Vector3
- func JointChildIndex(idx int32) int32
- func JointControl(idx, dof int32, vr JointControlVars) float32
- func JointDoF(idx, dof int32, vr JointDoFVars) float32
- func JointDoFIndex(idx, dof int32) int32
- func JointLinLambda(idx int32) math32.Vector3
- func JointPForce(idx int32) math32.Vector3
- func JointPPos(idx int32) math32.Vector3
- func JointPQuat(idx int32) math32.Quat
- func JointPTorque(idx int32) math32.Vector3
- func JointParentIndex(idx int32) int32
- func LimitDelta(v math32.Vector3, lim float32) math32.Vector3
- func OneIfNonzero(f float32) float32
- func PlaneEdge(edgeId int32, width, length float32, edge0, edge1 *math32.Vector3)
- func PlaneSDF(width, length float32, p math32.Vector3) float32
- func PositionalCorrection(err, derr float32, tfaQ, tfbQ math32.Quat, mInvA, mInvB float32, ...) float32
- func ReadFromGPU(vars ...GPUVars)
- func RunCollisionBroad(n int)
- func RunCollisionBroadCPU(n int)
- func RunCollisionBroadGPU(n int)
- func RunCollisionNarrow(n int)
- func RunCollisionNarrowCPU(n int)
- func RunCollisionNarrowGPU(n int)
- func RunDone(syncVars ...GPUVars)
- func RunDynamicsCurToNext(n int)
- func RunDynamicsCurToNextCPU(n int)
- func RunDynamicsCurToNextGPU(n int)
- func RunForcesFromJoints(n int)
- func RunForcesFromJointsCPU(n int)
- func RunForcesFromJointsGPU(n int)
- func RunGPUSync()
- func RunInitDynamics(n int)
- func RunInitDynamicsCPU(n int)
- func RunInitDynamicsGPU(n int)
- func RunOneCollisionBroad(n int, syncVars ...GPUVars)
- func RunOneCollisionNarrow(n int, syncVars ...GPUVars)
- func RunOneDynamicsCurToNext(n int, syncVars ...GPUVars)
- func RunOneForcesFromJoints(n int, syncVars ...GPUVars)
- func RunOneInitDynamics(n int, syncVars ...GPUVars)
- func RunOneStepBodyContactDeltas(n int, syncVars ...GPUVars)
- func RunOneStepBodyContacts(n int, syncVars ...GPUVars)
- func RunOneStepInit(n int, syncVars ...GPUVars)
- func RunOneStepIntegrateBodies(n int, syncVars ...GPUVars)
- func RunOneStepJointForces(n int, syncVars ...GPUVars)
- func RunOneStepSolveJoints(n int, syncVars ...GPUVars)
- func RunStepBodyContactDeltas(n int)
- func RunStepBodyContactDeltasCPU(n int)
- func RunStepBodyContactDeltasGPU(n int)
- func RunStepBodyContacts(n int)
- func RunStepBodyContactsCPU(n int)
- func RunStepBodyContactsGPU(n int)
- func RunStepInit(n int)
- func RunStepInitCPU(n int)
- func RunStepInitGPU(n int)
- func RunStepIntegrateBodies(n int)
- func RunStepIntegrateBodiesCPU(n int)
- func RunStepIntegrateBodiesGPU(n int)
- func RunStepJointForces(n int)
- func RunStepJointForcesCPU(n int)
- func RunStepJointForcesGPU(n int)
- func RunStepSolveJoints(n int)
- func RunStepSolveJointsCPU(n int)
- func RunStepSolveJointsGPU(n int)
- func SetBodyBounce(idx int32, val float32)
- func SetBodyCom(idx int32, pos math32.Vector3)
- func SetBodyDynamic(idx, dynIdx int32)
- func SetBodyFriction(idx int32, val float32)
- func SetBodyFrictionRolling(idx int32, val float32)
- func SetBodyFrictionTortion(idx int32, val float32)
- func SetBodyGroup(idx, w int32)
- func SetBodyHSize(idx int32, size math32.Vector3)
- func SetBodyInertia(idx int32, inertia math32.Matrix3)
- func SetBodyInvInertia(idx int32, invInertia math32.Matrix3)
- func SetBodyPos(idx int32, pos math32.Vector3)
- func SetBodyQuat(idx int32, rot math32.Quat)
- func SetBodyShape(idx int32, shape Shapes)
- func SetBodyThick(idx int32, val float32)
- func SetBodyWorld(idx, w int32)
- func SetBroadContactA(idx, bodIdx int32)
- func SetBroadContactB(idx, bodIdx int32)
- func SetBroadContactPointIdx(idx, ptIdx int32)
- func SetContactA(idx, bodIdx int32)
- func SetContactAAngDelta(idx int32, pos math32.Vector3)
- func SetContactADelta(idx int32, pos math32.Vector3)
- func SetContactAOff(idx int32, pos math32.Vector3)
- func SetContactAPoint(idx int32, pos math32.Vector3)
- func SetContactB(idx, bodIdx int32)
- func SetContactBAngDelta(idx int32, pos math32.Vector3)
- func SetContactBDelta(idx int32, pos math32.Vector3)
- func SetContactBOff(idx int32, pos math32.Vector3)
- func SetContactBPoint(idx int32, pos math32.Vector3)
- func SetContactNorm(idx int32, pos math32.Vector3)
- func SetContactPointIdx(idx, ptIdx int32)
- func SetDynamicAcc(idx, cni int32, acc math32.Vector3)
- func SetDynamicAngAcc(idx, cni int32, angAcc math32.Vector3)
- func SetDynamicAngDelta(idx, cni int32, angDelta math32.Vector3)
- func SetDynamicAngVel(idx, cni int32, angVel math32.Vector3)
- func SetDynamicBody(idx, bodyIdx int32)
- func SetDynamicDelta(idx, cni int32, delta math32.Vector3)
- func SetDynamicForce(idx, cni int32, force math32.Vector3)
- func SetDynamicPos(idx, cni int32, pos math32.Vector3)
- func SetDynamicQuat(idx, cni int32, rot math32.Quat)
- func SetDynamicTorque(idx, cni int32, torque math32.Vector3)
- func SetDynamicVel(idx, cni int32, vel math32.Vector3)
- func SetJointAngLambda(idx int32, t math32.Vector3)
- func SetJointAngularDoFN(idx, dofN int32)
- func SetJointAxis(idx, dof int32, axis math32.Vector3)
- func SetJointAxisDoF(didx int32, axis math32.Vector3)
- func SetJointCForce(idx int32, f math32.Vector3)
- func SetJointCPos(idx int32, pos math32.Vector3)
- func SetJointCQuat(idx int32, rot math32.Quat)
- func SetJointCTorque(idx int32, t math32.Vector3)
- func SetJointChild(idx, bodyIdx int32)
- func SetJointControl(idx, dof int32, vr JointControlVars, value float32)
- func SetJointControlForce(idx, dof int32, value float32)
- func SetJointDoF(idx, dof int32, vr JointDoFVars, value float32)
- func SetJointDoFIndex(idx, dof, dofIdx int32)
- func SetJointEnabled(idx int32, enabled bool)
- func SetJointLinLambda(idx int32, t math32.Vector3)
- func SetJointLinearDoFN(idx, dofN int32)
- func SetJointNoLinearRotation(idx int32, enabled bool)
- func SetJointPForce(idx int32, f math32.Vector3)
- func SetJointPPos(idx int32, pos math32.Vector3)
- func SetJointPQuat(idx int32, rot math32.Quat)
- func SetJointPTorque(idx int32, t math32.Vector3)
- func SetJointParent(idx, bodyIdx int32)
- func SetJointParentFixed(idx int32, enabled bool)
- func SetJointTargetAngle(idx, dof int32, angDeg, stiff float32)
- func SetJointTargetPos(idx, dof int32, pos, stiff float32)
- func SetJointTargetVel(idx, dof int32, vel, damp float32)
- func SetJointType(idx int32, typ JointTypes)
- func ShapePairContacts(a, b Shapes, infPlane bool, ba *int32) int32
- func SphereSDF(center math32.Vector3, radius float32, p math32.Vector3) float32
- func StepBodyContactDeltas(i uint32)
- func StepBodyContacts(i uint32)
- func StepBodyDeltas(di, bi int32, contacts bool, cWt float32, linDel, angDel math32.Vector3)
- func StepBodyKinetics(di, bi int32)
- func StepInit(i uint32)
- func StepIntegrateBodies(i uint32)
- func StepJointForces(i uint32)
- func StepSolveJoint(ji int32)
- func StepSolveJoints(i uint32)
- func StepsToMsec(steps int) int
- func SyncFromGPU(vars ...GPUVars)
- func ToGPU(vars ...GPUVars)
- func ToGPUTensorStrides()
- func VelocityAtPoint(lin, ang, r math32.Vector3) math32.Vector3
- func WorldsCollide(wa, wb int32) bool
- type BodyVars
- func (i BodyVars) Desc() string
- func (i BodyVars) Int64() int64
- func (i BodyVars) MarshalText() ([]byte, error)
- func (i *BodyVars) SetInt64(in int64)
- func (i *BodyVars) SetString(s string) error
- func (i BodyVars) String() string
- func (i *BodyVars) UnmarshalText(text []byte) error
- func (i BodyVars) Values() []enums.Enum
- type ContactVars
- func (i ContactVars) Desc() string
- func (i ContactVars) Int64() int64
- func (i ContactVars) MarshalText() ([]byte, error)
- func (i *ContactVars) SetInt64(in int64)
- func (i *ContactVars) SetString(s string) error
- func (i ContactVars) String() string
- func (i *ContactVars) UnmarshalText(text []byte) error
- func (i ContactVars) Values() []enums.Enum
- type DynamicVars
- func (i DynamicVars) Desc() string
- func (i DynamicVars) Int64() int64
- func (i DynamicVars) MarshalText() ([]byte, error)
- func (i *DynamicVars) SetInt64(in int64)
- func (i *DynamicVars) SetString(s string) error
- func (i DynamicVars) String() string
- func (i *DynamicVars) UnmarshalText(text []byte) error
- func (i DynamicVars) Values() []enums.Enum
- type GPUVars
- func (i GPUVars) Desc() string
- func (i GPUVars) Int64() int64
- func (i GPUVars) MarshalText() ([]byte, error)
- func (i *GPUVars) SetInt64(in int64)
- func (i *GPUVars) SetString(s string) error
- func (i GPUVars) String() string
- func (i *GPUVars) UnmarshalText(text []byte) error
- func (i GPUVars) Values() []enums.Enum
- type GeomData
- type JointControlVars
- func (i JointControlVars) Desc() string
- func (i JointControlVars) Int64() int64
- func (i JointControlVars) MarshalText() ([]byte, error)
- func (i *JointControlVars) SetInt64(in int64)
- func (i *JointControlVars) SetString(s string) error
- func (i JointControlVars) String() string
- func (i *JointControlVars) UnmarshalText(text []byte) error
- func (i JointControlVars) Values() []enums.Enum
- type JointDoFVars
- func (i JointDoFVars) Desc() string
- func (i JointDoFVars) Int64() int64
- func (i JointDoFVars) MarshalText() ([]byte, error)
- func (i *JointDoFVars) SetInt64(in int64)
- func (i *JointDoFVars) SetString(s string) error
- func (i JointDoFVars) String() string
- func (i *JointDoFVars) UnmarshalText(text []byte) error
- func (i JointDoFVars) Values() []enums.Enum
- type JointTypes
- func (i JointTypes) Desc() string
- func (i JointTypes) Int64() int64
- func (i JointTypes) MarshalText() ([]byte, error)
- func (i *JointTypes) SetInt64(in int64)
- func (i *JointTypes) SetString(s string) error
- func (i JointTypes) String() string
- func (i *JointTypes) UnmarshalText(text []byte) error
- func (i JointTypes) Values() []enums.Enum
- type JointVars
- func (i JointVars) Desc() string
- func (i JointVars) Int64() int64
- func (i JointVars) MarshalText() ([]byte, error)
- func (i *JointVars) SetInt64(in int64)
- func (i *JointVars) SetString(s string) error
- func (i JointVars) String() string
- func (i *JointVars) UnmarshalText(text []byte) error
- func (i JointVars) Values() []enums.Enum
- type Model
- func (ml *Model) Config()
- func (ml *Model) ConfigBodies()
- func (ml *Model) ConfigBodyCollidePairs()
- func (ml *Model) ConfigJoints()
- func (ml *Model) GPUInit()
- func (ml *Model) Init()
- func (ml *Model) InitControlState()
- func (ml *Model) InitState()
- func (ml *Model) IsChildDynamic(dip, dic int32) bool
- func (ml *Model) JointDefaults(idx int32)
- func (ml *Model) JointDoFDefaults(didx int32)
- func (ml *Model) NewBody(shape Shapes, hsize, pos math32.Vector3, rot math32.Quat) int32
- func (ml *Model) NewDynamic(shape Shapes, mass float32, hsize, pos math32.Vector3, rot math32.Quat) (bodyIdx, dynIdx int32)
- func (ml *Model) NewJointBall(parent, child int32, ppos, cpos math32.Vector3) int32
- func (ml *Model) NewJointD6(parent, child int32, ppos, cpos math32.Vector3, linDoF, angDoF int32) int32
- func (ml *Model) NewJointDistance(parent, child int32, ppos, cpos math32.Vector3, minDist, maxDist float32) int32
- func (ml *Model) NewJointFixed(parent, child int32, ppos, cpos math32.Vector3) int32
- func (ml *Model) NewJointFree(parent, child int32, ppos, cpos math32.Vector3) int32
- func (ml *Model) NewJointPlaneXZ(parent, child int32, ppos, cpos math32.Vector3) int32
- func (ml *Model) NewJointPrismatic(parent, child int32, ppos, cpos, axis math32.Vector3) int32
- func (ml *Model) NewJointRevolute(parent, child int32, ppos, cpos, axis math32.Vector3) int32
- func (ml *Model) NewObject() int32
- func (ml *Model) ReplicasBodyIndexes(bi, replica int32) (bodyIdx, dynIdx int32)
- func (ml *Model) ReplicasJointIndex(ji, replica int32) int32
- func (ml *Model) Reset()
- func (ml *Model) SetAsCurrent()
- func (ml *Model) SetAsCurrentVars()
- func (ml *Model) SetMass(idx int32, shape Shapes, size math32.Vector3, mass float32)
- func (ml *Model) SetMaxContacts()
- func (ml *Model) Step()
- func (ml *Model) StepBodyContacts()
- func (ml *Model) StepCollision()
- func (ml *Model) StepGet(vars ...GPUVars)
- func (ml *Model) StepIntegrateBodies()
- func (ml *Model) StepJointForces()
- func (ml *Model) StepSolveJoints()
- func (ml *Model) ToGPUInfra()
- func (ml *Model) TotalKineticEnergy() float32
- type PhysicsParams
- type Shapes
- func (sh Shapes) BBox(sz math32.Vector3) math32.Box3
- func (i Shapes) Desc() string
- func (sh Shapes) Inertia(sz math32.Vector3, mass float32) math32.Matrix3
- func (i Shapes) Int64() int64
- func (i Shapes) MarshalText() ([]byte, error)
- func (sh Shapes) Radius(sz math32.Vector3) float32
- func (i *Shapes) SetInt64(in int64)
- func (i *Shapes) SetString(s string) error
- func (i Shapes) String() string
- func (i *Shapes) UnmarshalText(text []byte) error
- func (i Shapes) Values() []enums.Enum
Constants ¶
const BroadContactVarsN = ContactAPointX
number of broad-phase contact values: just the indexes
const JointLimitUnlimited = 1e10
Sentinel value for unlimited joint limits
Variables ¶
var ( // GPUInitialized is true once the GPU system has been initialized. // Prevents multiple initializations. GPUInitialized bool // ComputeGPU is the compute gpu device. // Set this prior to calling GPUInit() to use an existing device. ComputeGPU *gpu.GPU // BorrowedGPU is true if our ComputeGPU is set externally, // versus created specifically for this system. If external, // we don't release it. BorrowedGPU bool // UseGPU indicates whether to use GPU vs. CPU. UseGPU bool )
var ( // Params are global parameters. //gosl:group Params Params []PhysicsParams // Bodies are the rigid body elements (dynamic and static), // specifying the constant, non-dynamic properties, // which is initial state for dynamics. // [body][BodyVarsN] //gosl:group Bodies //gosl:dims 2 Bodies *tensor.Float32 // Objects is a list of joint indexes for each object, where each object // contains all the joints interconnecting an overlapping set of bodies. // This is known as an articulation in other physics software. // Joints must be added in parent -> child order within objects, as joints // are updated in sequential order within object. First element is n joints. // [object][MaxObjectJoints+1] //gosl:dims 2 Objects *tensor.Int32 // BodyJoints is a list of joint indexes for each dynamic body, for aggregating. // [dyn body][parent, child][maxjointsperbody] //gosl:dims 3 BodyJoints *tensor.Int32 // Joints is a list of permanent joints connecting bodies, // which do not change (no dynamic variables, except temps). // [joint][JointVars] //gosl:dims 2 Joints *tensor.Float32 // JointDoFs is a list of joint DoF parameters, allocated per joint. // [dof][JointDoFVars] //gosl:dims 2 JointDoFs *tensor.Float32 // BodyCollidePairs are pairs of Body indexes that could potentially collide // based on precomputed collision logic, using World, Group, and Joint indexes. // [BodyCollidePairsN][2] //gosl:dims 2 BodyCollidePairs *tensor.Int32 // Dynamics are the dynamic rigid body elements: these actually move. // Two alternating states are used: Params.Cur and Params.Next. // [dyn body][cur/next][DynamicVarsN] //gosl:group Dynamics //gosl:dims 3 Dynamics *tensor.Float32 // BroadContactsN has number of points of broad contact // between bodies. [1] //gosl:dims 1 BroadContactsN *tensor.Int32 // BroadContacts are the results of broad-phase contact processing, // establishing possible points of contact between bodies. // [ContactsMax][BroadContactVarsN] //gosl:dims 2 BroadContacts *tensor.Float32 // ContactsN has number of points of narrow (final) contact // between bodies. [1] //gosl:dims 1 ContactsN *tensor.Int32 // Contacts are the results of narrow-phase contact processing, // where only actual contacts with fully-specified values are present. // [ContactsMax][ContactVarsN] //gosl:dims 2 Contacts *tensor.Float32 // JointControls are dynamic joint control inputs, per joint DoF // (in correspondence with [JointDoFs]). This can be uploaded to the // GPU at every step. // [dof][JointControlVarsN] //gosl:group Controls //gosl:dims 2 JointControls *tensor.Float32 )
vars are all the global vars for axon GPU / CPU computation.
var GPUSystem *gpu.ComputeSystem
GPUSystem is a GPU compute System with kernels operating on the same set of data variables.
var TensorStrides tensor.Uint32
Tensor stride variables
Functions ¶
func AddBroadContacts ¶
func AddBroadContacts(biA, biB, nci, ncA, ncB int32)
AddBroadContacts adds broad-phase contact records in prep for narrow phase.
func AngularAccelAt ¶
AngularAccelAt returns the angular acceleration vector of given dynamic body index and Next index, relative to given rotation axis at given point relative to the structural center of the given dynamic body. For example, to get rotation around the XZ plane, axis = (0,1,0) and the acceleration value will show up in the Z axis for an X-axis point, and vice-versa (X for a Z-axis point). This uses DynamicAngAcc which is computed after each step (into Next).
func AngularCorrection ¶
func AngularVelocityAt ¶
AngularVelocityAt returns the angular velocity vector of given dynamic body index and Next index, relative to given rotation axis at given point relative to the structural center of the given dynamic body. For example, to get rotation around the XZ plane, axis = (0,1,0) and the velocity value will show up in the Z axis for an X-axis point, and vice-versa (X for a Z-axis point). This uses DynamicAngVel which is computed after each step (into Next).
func BodyDynamicPos ¶
BodyDynamicPos gets the position for dynamic bodies or static position if not dynamic. cni is the current / next index.
func BodyDynamicQuat ¶
BodyDynamicQuat gets the quat rotation for dynamic bodies or static rotation if not dynamic. cni is the current / next index.
func BodyInertia ¶
func BodyInvInertia ¶
func BoxVertex ¶
box vertex numbering:
6---7 |\ |\ y | 2-+-3 | 4-+-5 | z \| \| \| o---x 0---1
get the vertex of the box given its ID (0-7)
func ClosestEdgeBox ¶
find point on edge closest to box, return its barycentric edge coordinate
func ClosestEdgeCapsule ¶
find point on edge closest to capsule, return its barycentric edge coordinate
func ClosestEdgePlane ¶
find point on edge closest to plane, return its barycentric edge coordinate
func ClosestPointBox ¶
closest point to box surface
func ClosestPointPlane ¶
ClosestPointPlane projects the point onto the quad in the xz plane (if size > 0.0), otherwise infinite.
func ColBoxBox ¶
func ColBoxBox(cpi, maxIter int32, gdA *GeomData, gdB *GeomData, pA, pB, norm *math32.Vector3) float32
Handle collision between two boxes (gdA and gdB).
func ColBoxCapsule ¶
func ColBoxCapsule(cpi, maxIter int32, gdA *GeomData, gdB *GeomData, pA, pB, norm *math32.Vector3) float32
Handle collision between a box (gdA) and a capsule (gdB).
func ColBoxPlane ¶
func ColBoxPlane(cpi, maxIter int32, gdA *GeomData, gdB *GeomData, pA, pB, norm *math32.Vector3) float32
Handle collision between a box (gdA) and a plane (gdB).
func ColCapsuleCapsule ¶
func ColCapsuleCapsule(cpi, maxIter int32, gdA *GeomData, gdB *GeomData, pA, pB, norm *math32.Vector3) float32
Handle collision between two capsules (gdA and gdB).
func ColCapsulePlane ¶
func ColCylinderPlane ¶
func ColCylinderPlane(cpi, maxIter int32, gdA *GeomData, gdB *GeomData, pA, pB, norm *math32.Vector3) float32
Handle collision between a cylinder (geo_a) and an infinite plane (geo_b).
func ColSphereBox ¶
func ColSphereBox(cpi, maxIter int32, gdA *GeomData, gdB *GeomData, pA, pB, norm *math32.Vector3) float32
Handle collision between a sphere (gdA) and a box (gdB).
func ColSphereCapsule ¶
func ColSphereCapsule(cpi, maxIter int32, gdA *GeomData, gdB *GeomData, pA, pB, norm *math32.Vector3) float32
Handle collision between a sphere (gdA) and a capsule (gdB).
func ColSpherePlane ¶
func ColSpherePlane(cpi, maxIter int32, gdA *GeomData, gdB *GeomData, pA, pB, norm *math32.Vector3) float32
Handle collision between a sphere (gdA) and a plane (gdB).
func ColSphereSphere ¶
func CollisionBroad ¶
func CollisionBroad(i uint32)
CollisionBroad performs broad-phase collision detection, generating Contacts.
func CollisionNarrow ¶
func CollisionNarrow(i uint32)
CollisionNarrow performs narrow-phase collision on Contacts.
func ContactAAngDelta ¶
func ContactADelta ¶
func ContactAOff ¶
func ContactAPoint ¶
func ContactBAngDelta ¶
func ContactBDelta ¶
func ContactBOff ¶
func ContactBPoint ¶
func ContactConstraint ¶
func ContactNorm ¶
func ContactPoints ¶
func ContactPoints(dist, margin float32, gdA *GeomData, gdB *GeomData, ptA, ptB, norm math32.Vector3, ctA, ctB, offA, offB *math32.Vector3, distActual, offMagA, offMagB *float32) bool
ContactPoints is the common final pathway for all Col* shape-specific collision functions, first determining if the computed distance is within the given margin and returning false if not (not a true contact). Otherwise, sets the actual points of contact and their offsets based on ptA, ptB, norm and dist values returned from collision functions. The actual distance is reduced by the radius values for Sphere, Capsule, and Cone types, and is returned in distActual. This is broken out here to support independent testing of the collision functions.
func DynamicAcc ¶
func DynamicAngAcc ¶
func DynamicAngDelta ¶
func DynamicAngVel ¶
func DynamicBody ¶
func DynamicDelta ¶
func DynamicForce ¶
func DynamicPos ¶
func DynamicQuat ¶
func DynamicTorque ¶
func DynamicVel ¶
func DynamicsCurToNext ¶
func DynamicsCurToNext(i uint32)
DynamicsCurToNext copies Dynamics state from Cur to Next.
func ForcesFromJoints ¶
func ForcesFromJoints(i uint32)
ForcesFromJoints gathers forces and torques from joints per dynamic
func GPUInit ¶
func GPUInit()
GPUInit initializes the GPU compute system, configuring system(s), variables and kernels. It is safe to call multiple times: detects if already run.
func GPURelease ¶
func GPURelease()
GPURelease releases the GPU compute system resources. Call this at program exit.
func GetBodyDynamic ¶
func GetBodyGroup ¶
func GetBodyWorld ¶
func GetBroadContactA ¶
func GetBroadContactB ¶
func GetBroadContactPointIdx ¶
func GetContactA ¶
func GetContactB ¶
func GetContactPointIdx ¶
func GetJointAngularDoFN ¶
func GetJointEnabled ¶
func GetJointLinearDoFN ¶
func GetJointParentFixed ¶
func GetJointTargetPos ¶
GetJointTargetPos returns the target position for given joint, DoF.
func GetJointTargetVel ¶
GetJointTargetVel returns the target velocity for given joint, DoF.
func GroupsCollide ¶
func InitDynamics ¶
func InitDynamics(i uint32)
InitDynamics copies Body initial state to dynamic state (cur and next).
func InitGeomData ¶
func JointAngLambda ¶
func JointAxisDoF ¶
func JointAxisLimitsUpdate ¶
func JointAxisLimitsUpdate(dof int32, axis math32.Vector3, lower, upper float32, axisLimitsD, axisLimitsA *math32.Vector3)
update the 3D linear/angular limits (spatial_vector [lower, upper]) given the axis vector and limits
func JointAxisTarget ¶
func JointCForce ¶
func JointCQuat ¶
func JointCTorque ¶
func JointChildIndex ¶
func JointControl ¶
func JointControl(idx, dof int32, vr JointControlVars) float32
func JointDoF ¶
func JointDoF(idx, dof int32, vr JointDoFVars) float32
func JointDoFIndex ¶
func JointLinLambda ¶
func JointPForce ¶
func JointPQuat ¶
func JointPTorque ¶
func JointParentIndex ¶
func LimitDelta ¶
LimitDelta limits the magnitude of a delta vector
func OneIfNonzero ¶
func PositionalCorrection ¶
func ReadFromGPU ¶
func ReadFromGPU(vars ...GPUVars)
ReadFromGPU starts the process of copying vars to the GPU.
func RunCollisionBroad ¶
func RunCollisionBroad(n int)
RunCollisionBroad runs the CollisionBroad kernel with given number of elements, on either the CPU or GPU depending on the UseGPU variable. Can call multiple Run* kernels in a row, which are then all launched in the same command submission on the GPU, which is by far the most efficient. MUST call RunDone (with optional vars to sync) after all Run calls. Alternatively, a single-shot RunOneCollisionBroad call does Run and Done for a single run-and-sync case.
func RunCollisionBroadCPU ¶
func RunCollisionBroadCPU(n int)
RunCollisionBroadCPU runs the CollisionBroad kernel on the CPU.
func RunCollisionBroadGPU ¶
func RunCollisionBroadGPU(n int)
RunCollisionBroadGPU runs the CollisionBroad kernel on the GPU. See RunCollisionBroad for more info.
func RunCollisionNarrow ¶
func RunCollisionNarrow(n int)
RunCollisionNarrow runs the CollisionNarrow kernel with given number of elements, on either the CPU or GPU depending on the UseGPU variable. Can call multiple Run* kernels in a row, which are then all launched in the same command submission on the GPU, which is by far the most efficient. MUST call RunDone (with optional vars to sync) after all Run calls. Alternatively, a single-shot RunOneCollisionNarrow call does Run and Done for a single run-and-sync case.
func RunCollisionNarrowCPU ¶
func RunCollisionNarrowCPU(n int)
RunCollisionNarrowCPU runs the CollisionNarrow kernel on the CPU.
func RunCollisionNarrowGPU ¶
func RunCollisionNarrowGPU(n int)
RunCollisionNarrowGPU runs the CollisionNarrow kernel on the GPU. See RunCollisionNarrow for more info.
func RunDone ¶
func RunDone(syncVars ...GPUVars)
RunDone must be called after Run* calls to start compute kernels. This actually submits the kernel jobs to the GPU, and adds commands to synchronize the given variables back from the GPU to the CPU. After this function completes, the GPU results will be available in the specified variables.
func RunDynamicsCurToNext ¶
func RunDynamicsCurToNext(n int)
RunDynamicsCurToNext runs the DynamicsCurToNext kernel with given number of elements, on either the CPU or GPU depending on the UseGPU variable. Can call multiple Run* kernels in a row, which are then all launched in the same command submission on the GPU, which is by far the most efficient. MUST call RunDone (with optional vars to sync) after all Run calls. Alternatively, a single-shot RunOneDynamicsCurToNext call does Run and Done for a single run-and-sync case.
func RunDynamicsCurToNextCPU ¶
func RunDynamicsCurToNextCPU(n int)
RunDynamicsCurToNextCPU runs the DynamicsCurToNext kernel on the CPU.
func RunDynamicsCurToNextGPU ¶
func RunDynamicsCurToNextGPU(n int)
RunDynamicsCurToNextGPU runs the DynamicsCurToNext kernel on the GPU. See RunDynamicsCurToNext for more info.
func RunForcesFromJoints ¶
func RunForcesFromJoints(n int)
RunForcesFromJoints runs the ForcesFromJoints kernel with given number of elements, on either the CPU or GPU depending on the UseGPU variable. Can call multiple Run* kernels in a row, which are then all launched in the same command submission on the GPU, which is by far the most efficient. MUST call RunDone (with optional vars to sync) after all Run calls. Alternatively, a single-shot RunOneForcesFromJoints call does Run and Done for a single run-and-sync case.
func RunForcesFromJointsCPU ¶
func RunForcesFromJointsCPU(n int)
RunForcesFromJointsCPU runs the ForcesFromJoints kernel on the CPU.
func RunForcesFromJointsGPU ¶
func RunForcesFromJointsGPU(n int)
RunForcesFromJointsGPU runs the ForcesFromJoints kernel on the GPU. See RunForcesFromJoints for more info.
func RunGPUSync ¶
func RunGPUSync()
RunGPUSync can be called to synchronize data between CPU and GPU. Any prior ToGPU* calls will execute to send data to the GPU, and any subsequent RunDone* calls will copy data back from the GPU.
func RunInitDynamics ¶
func RunInitDynamics(n int)
RunInitDynamics runs the InitDynamics kernel with given number of elements, on either the CPU or GPU depending on the UseGPU variable. Can call multiple Run* kernels in a row, which are then all launched in the same command submission on the GPU, which is by far the most efficient. MUST call RunDone (with optional vars to sync) after all Run calls. Alternatively, a single-shot RunOneInitDynamics call does Run and Done for a single run-and-sync case.
func RunInitDynamicsCPU ¶
func RunInitDynamicsCPU(n int)
RunInitDynamicsCPU runs the InitDynamics kernel on the CPU.
func RunInitDynamicsGPU ¶
func RunInitDynamicsGPU(n int)
RunInitDynamicsGPU runs the InitDynamics kernel on the GPU. See RunInitDynamics for more info.
func RunOneCollisionBroad ¶
RunOneCollisionBroad runs the CollisionBroad kernel with given number of elements, on either the CPU or GPU depending on the UseGPU variable. This version then calls RunDone with the given variables to sync after the Run, for a single-shot Run-and-Done call. If multiple kernels can be run in sequence, it is much more efficient to do multiple Run* calls followed by a RunDone call.
func RunOneCollisionNarrow ¶
RunOneCollisionNarrow runs the CollisionNarrow kernel with given number of elements, on either the CPU or GPU depending on the UseGPU variable. This version then calls RunDone with the given variables to sync after the Run, for a single-shot Run-and-Done call. If multiple kernels can be run in sequence, it is much more efficient to do multiple Run* calls followed by a RunDone call.
func RunOneDynamicsCurToNext ¶
RunOneDynamicsCurToNext runs the DynamicsCurToNext kernel with given number of elements, on either the CPU or GPU depending on the UseGPU variable. This version then calls RunDone with the given variables to sync after the Run, for a single-shot Run-and-Done call. If multiple kernels can be run in sequence, it is much more efficient to do multiple Run* calls followed by a RunDone call.
func RunOneForcesFromJoints ¶
RunOneForcesFromJoints runs the ForcesFromJoints kernel with given number of elements, on either the CPU or GPU depending on the UseGPU variable. This version then calls RunDone with the given variables to sync after the Run, for a single-shot Run-and-Done call. If multiple kernels can be run in sequence, it is much more efficient to do multiple Run* calls followed by a RunDone call.
func RunOneInitDynamics ¶
RunOneInitDynamics runs the InitDynamics kernel with given number of elements, on either the CPU or GPU depending on the UseGPU variable. This version then calls RunDone with the given variables to sync after the Run, for a single-shot Run-and-Done call. If multiple kernels can be run in sequence, it is much more efficient to do multiple Run* calls followed by a RunDone call.
func RunOneStepBodyContactDeltas ¶
RunOneStepBodyContactDeltas runs the StepBodyContactDeltas kernel with given number of elements, on either the CPU or GPU depending on the UseGPU variable. This version then calls RunDone with the given variables to sync after the Run, for a single-shot Run-and-Done call. If multiple kernels can be run in sequence, it is much more efficient to do multiple Run* calls followed by a RunDone call.
func RunOneStepBodyContacts ¶
RunOneStepBodyContacts runs the StepBodyContacts kernel with given number of elements, on either the CPU or GPU depending on the UseGPU variable. This version then calls RunDone with the given variables to sync after the Run, for a single-shot Run-and-Done call. If multiple kernels can be run in sequence, it is much more efficient to do multiple Run* calls followed by a RunDone call.
func RunOneStepInit ¶
RunOneStepInit runs the StepInit kernel with given number of elements, on either the CPU or GPU depending on the UseGPU variable. This version then calls RunDone with the given variables to sync after the Run, for a single-shot Run-and-Done call. If multiple kernels can be run in sequence, it is much more efficient to do multiple Run* calls followed by a RunDone call.
func RunOneStepIntegrateBodies ¶
RunOneStepIntegrateBodies runs the StepIntegrateBodies kernel with given number of elements, on either the CPU or GPU depending on the UseGPU variable. This version then calls RunDone with the given variables to sync after the Run, for a single-shot Run-and-Done call. If multiple kernels can be run in sequence, it is much more efficient to do multiple Run* calls followed by a RunDone call.
func RunOneStepJointForces ¶
RunOneStepJointForces runs the StepJointForces kernel with given number of elements, on either the CPU or GPU depending on the UseGPU variable. This version then calls RunDone with the given variables to sync after the Run, for a single-shot Run-and-Done call. If multiple kernels can be run in sequence, it is much more efficient to do multiple Run* calls followed by a RunDone call.
func RunOneStepSolveJoints ¶
RunOneStepSolveJoints runs the StepSolveJoints kernel with given number of elements, on either the CPU or GPU depending on the UseGPU variable. This version then calls RunDone with the given variables to sync after the Run, for a single-shot Run-and-Done call. If multiple kernels can be run in sequence, it is much more efficient to do multiple Run* calls followed by a RunDone call.
func RunStepBodyContactDeltas ¶
func RunStepBodyContactDeltas(n int)
RunStepBodyContactDeltas runs the StepBodyContactDeltas kernel with given number of elements, on either the CPU or GPU depending on the UseGPU variable. Can call multiple Run* kernels in a row, which are then all launched in the same command submission on the GPU, which is by far the most efficient. MUST call RunDone (with optional vars to sync) after all Run calls. Alternatively, a single-shot RunOneStepBodyContactDeltas call does Run and Done for a single run-and-sync case.
func RunStepBodyContactDeltasCPU ¶
func RunStepBodyContactDeltasCPU(n int)
RunStepBodyContactDeltasCPU runs the StepBodyContactDeltas kernel on the CPU.
func RunStepBodyContactDeltasGPU ¶
func RunStepBodyContactDeltasGPU(n int)
RunStepBodyContactDeltasGPU runs the StepBodyContactDeltas kernel on the GPU. See RunStepBodyContactDeltas for more info.
func RunStepBodyContacts ¶
func RunStepBodyContacts(n int)
RunStepBodyContacts runs the StepBodyContacts kernel with given number of elements, on either the CPU or GPU depending on the UseGPU variable. Can call multiple Run* kernels in a row, which are then all launched in the same command submission on the GPU, which is by far the most efficient. MUST call RunDone (with optional vars to sync) after all Run calls. Alternatively, a single-shot RunOneStepBodyContacts call does Run and Done for a single run-and-sync case.
func RunStepBodyContactsCPU ¶
func RunStepBodyContactsCPU(n int)
RunStepBodyContactsCPU runs the StepBodyContacts kernel on the CPU.
func RunStepBodyContactsGPU ¶
func RunStepBodyContactsGPU(n int)
RunStepBodyContactsGPU runs the StepBodyContacts kernel on the GPU. See RunStepBodyContacts for more info.
func RunStepInit ¶
func RunStepInit(n int)
RunStepInit runs the StepInit kernel with given number of elements, on either the CPU or GPU depending on the UseGPU variable. Can call multiple Run* kernels in a row, which are then all launched in the same command submission on the GPU, which is by far the most efficient. MUST call RunDone (with optional vars to sync) after all Run calls. Alternatively, a single-shot RunOneStepInit call does Run and Done for a single run-and-sync case.
func RunStepInitCPU ¶
func RunStepInitCPU(n int)
RunStepInitCPU runs the StepInit kernel on the CPU.
func RunStepInitGPU ¶
func RunStepInitGPU(n int)
RunStepInitGPU runs the StepInit kernel on the GPU. See RunStepInit for more info.
func RunStepIntegrateBodies ¶
func RunStepIntegrateBodies(n int)
RunStepIntegrateBodies runs the StepIntegrateBodies kernel with given number of elements, on either the CPU or GPU depending on the UseGPU variable. Can call multiple Run* kernels in a row, which are then all launched in the same command submission on the GPU, which is by far the most efficient. MUST call RunDone (with optional vars to sync) after all Run calls. Alternatively, a single-shot RunOneStepIntegrateBodies call does Run and Done for a single run-and-sync case.
func RunStepIntegrateBodiesCPU ¶
func RunStepIntegrateBodiesCPU(n int)
RunStepIntegrateBodiesCPU runs the StepIntegrateBodies kernel on the CPU.
func RunStepIntegrateBodiesGPU ¶
func RunStepIntegrateBodiesGPU(n int)
RunStepIntegrateBodiesGPU runs the StepIntegrateBodies kernel on the GPU. See RunStepIntegrateBodies for more info.
func RunStepJointForces ¶
func RunStepJointForces(n int)
RunStepJointForces runs the StepJointForces kernel with given number of elements, on either the CPU or GPU depending on the UseGPU variable. Can call multiple Run* kernels in a row, which are then all launched in the same command submission on the GPU, which is by far the most efficient. MUST call RunDone (with optional vars to sync) after all Run calls. Alternatively, a single-shot RunOneStepJointForces call does Run and Done for a single run-and-sync case.
func RunStepJointForcesCPU ¶
func RunStepJointForcesCPU(n int)
RunStepJointForcesCPU runs the StepJointForces kernel on the CPU.
func RunStepJointForcesGPU ¶
func RunStepJointForcesGPU(n int)
RunStepJointForcesGPU runs the StepJointForces kernel on the GPU. See RunStepJointForces for more info.
func RunStepSolveJoints ¶
func RunStepSolveJoints(n int)
RunStepSolveJoints runs the StepSolveJoints kernel with given number of elements, on either the CPU or GPU depending on the UseGPU variable. Can call multiple Run* kernels in a row, which are then all launched in the same command submission on the GPU, which is by far the most efficient. MUST call RunDone (with optional vars to sync) after all Run calls. Alternatively, a single-shot RunOneStepSolveJoints call does Run and Done for a single run-and-sync case.
func RunStepSolveJointsCPU ¶
func RunStepSolveJointsCPU(n int)
RunStepSolveJointsCPU runs the StepSolveJoints kernel on the CPU.
func RunStepSolveJointsGPU ¶
func RunStepSolveJointsGPU(n int)
RunStepSolveJointsGPU runs the StepSolveJoints kernel on the GPU. See RunStepSolveJoints for more info.
func SetBodyBounce ¶
SetBodyBounce specifies the COR or coefficient of restitution (0..1), which determines how elastic the collision is, i.e., final velocity / initial velocity.
func SetBodyCom ¶
func SetBodyDynamic ¶
func SetBodyDynamic(idx, dynIdx int32)
func SetBodyFriction ¶
SetBodyFriction is the standard coefficient for linear friction (mu).
func SetBodyFrictionRolling ¶
SetBodyFrictionRolling is resistance to rolling motion at contact.
func SetBodyFrictionTortion ¶
SetBodyFrictionTortion is resistance to spinning at the contact point.
func SetBodyGroup ¶
func SetBodyGroup(idx, w int32)
SetBodyGroup partitions bodies within worlds into different groups for collision detection. 0 does not collide with anything. Negative numbers are global within a world, except they don't collide amongst themselves (all non-dynamic bodies should go in -1 because they don't collide amongst each-other, but do potentially collide with dynamics). Positive numbers only collide amongst themselves, and with negative groups, but not other positive groups. To avoid unwanted collisions, put bodies into separate groups. There is an automatic constraint that the two objects within a single joint do not collide with each other, so this does not need to be handled here.
func SetBodyHSize ¶
func SetBodyInertia ¶
func SetBodyInvInertia ¶
func SetBodyPos ¶
func SetBodyQuat ¶
func SetBodyShape ¶
func SetBodyThick ¶
SetBodyThick specifies the thickness of the body, as a hollow shape. if 0, then it is solid.
func SetBodyWorld ¶
func SetBodyWorld(idx, w int32)
SetBodyWorld partitions bodies into different worlds for collision detection: Global bodies = -1 can collide with everything; otherwise only items within the same world collide.
func SetBroadContactA ¶
func SetBroadContactA(idx, bodIdx int32)
func SetBroadContactB ¶
func SetBroadContactB(idx, bodIdx int32)
func SetBroadContactPointIdx ¶
func SetBroadContactPointIdx(idx, ptIdx int32)
func SetContactA ¶
func SetContactA(idx, bodIdx int32)
func SetContactAAngDelta ¶
func SetContactADelta ¶
func SetContactAOff ¶
func SetContactAPoint ¶
func SetContactB ¶
func SetContactB(idx, bodIdx int32)
func SetContactBAngDelta ¶
func SetContactBDelta ¶
func SetContactBOff ¶
func SetContactBPoint ¶
func SetContactNorm ¶
func SetContactPointIdx ¶
func SetContactPointIdx(idx, ptIdx int32)
func SetDynamicAcc ¶
func SetDynamicAngAcc ¶
func SetDynamicAngDelta ¶
func SetDynamicAngVel ¶
func SetDynamicBody ¶
func SetDynamicBody(idx, bodyIdx int32)
func SetDynamicDelta ¶
func SetDynamicForce ¶
func SetDynamicPos ¶
func SetDynamicQuat ¶
func SetDynamicTorque ¶
func SetDynamicVel ¶
func SetJointAngLambda ¶
func SetJointAngularDoFN ¶
func SetJointAngularDoFN(idx, dofN int32)
func SetJointAxis ¶
func SetJointAxisDoF ¶
func SetJointCForce ¶
func SetJointCPos ¶
func SetJointCQuat ¶
func SetJointCTorque ¶
func SetJointChild ¶
func SetJointChild(idx, bodyIdx int32)
func SetJointControl ¶
func SetJointControl(idx, dof int32, vr JointControlVars, value float32)
SetJointControl sets the control for given joint, dof and parameter to given value.
func SetJointControlForce ¶
SetJointControlForce sets the force for given joint, dof to given value.
func SetJointDoF ¶
func SetJointDoF(idx, dof int32, vr JointDoFVars, value float32)
func SetJointDoFIndex ¶
func SetJointDoFIndex(idx, dof, dofIdx int32)
func SetJointEnabled ¶
func SetJointLinLambda ¶
func SetJointLinearDoFN ¶
func SetJointLinearDoFN(idx, dofN int32)
func SetJointPForce ¶
func SetJointPPos ¶
func SetJointPQuat ¶
func SetJointPTorque ¶
func SetJointParent ¶
func SetJointParent(idx, bodyIdx int32)
func SetJointParentFixed ¶
func SetJointTargetAngle ¶
SetJointTargetAngle sets the target angular position and stiffness for given joint, DoF to given values. Stiffness determines how strongly the joint constraint is enforced (0 = not at all; 1000+ = strongly). Angle is in Degrees, not radians. Usable range is within -180..180 which is enforced, and values near the edge can be unstable at higher stiffness levels.
func SetJointTargetPos ¶
SetJointTargetPos sets the target position and stiffness for given joint, DoF to given values. Stiffness determines how strongly the joint constraint is enforced (0 = not at all; 1000+ = strongly). For angular joints, values are in radians, see also SetJointTargetAngle.
func SetJointTargetVel ¶
SetJointTargetVel sets the target velocity and damping for given joint, DoF to given values. Damping determines how strongly the joint constraint is enforced (0 = not at all; 1000+ = strongly).
func SetJointType ¶
func SetJointType(idx int32, typ JointTypes)
func ShapePairContacts ¶
ShapePairContacts returns the number of contact points possible for given pair of shapes. a <= b ordering. returns from a to b, ba is from b to a (mostly 0). infPlane means that a is a Plane and it is infinite (size = 0).
func StepBodyContactDeltas ¶
func StepBodyContactDeltas(i uint32)
StepBodyContactDeltas gathers raw deltas, angDeltas from contacts per dynamic and computes updated deltas integrated via StepBodyDeltas.
func StepBodyContacts ¶
func StepBodyContacts(i uint32)
StepBodyContacts generates contact forces for bodies.
func StepBodyDeltas ¶
StepBodyDeltas updates Next position with deltas from joints or contacts (if contacts true). Also updates kinetics (velocity and acceleration) based on position & orientation changes if contacts=true (usually just 1 iteration).
func StepBodyKinetics ¶
func StepBodyKinetics(di, bi int32)
StepBodyKinetics computes the empirical velocities and accelerations from the final changes in position and orientation from Cur to Next.
func StepIntegrateBodies ¶
func StepIntegrateBodies(i uint32)
StepIntegrateBodies applies forces to update pos and deltas
func StepSolveJoint ¶
func StepSolveJoint(ji int32)
StepSolveJoint applies target positions to linear DoFs. Position is updated prior to computing angulars.
func StepSolveJoints ¶
func StepSolveJoints(i uint32)
StepSolveJoints applies target positions to joints. This is per Object because it needs to solve joints in parent -> child order.
func StepsToMsec ¶
StepsToMsec returns the given number of individual Step calls converted into milliseconds, suitable for driving controls, Using the currently-set Params.
func SyncFromGPU ¶
func SyncFromGPU(vars ...GPUVars)
SyncFromGPU synchronizes vars from the GPU to the actual variable.
func ToGPUTensorStrides ¶
func ToGPUTensorStrides()
ToGPUTensorStrides gets tensor strides and starts copying to the GPU.
func WorldsCollide ¶
Types ¶
type BodyVars ¶
type BodyVars int32 //enums:enum
BodyVars are body state variables stored in tensor.Float32
const ( // BodyShape is the shape type of the object, as a Shapes type. BodyShape BodyVars = iota // BodyDynamic is the index into Dynamics for this body, // which is -1 for static bodies. Use this to get current // Pos and Quat values for a dynamic body. BodyDynamic // BodyWorld partitions bodies into different worlds for // collision detection: Global bodies = -1 can collide with // everything; otherwise only items within the same world collide. // NewBody uses [World.CurrentWorld] to initialize. BodyWorld // BodyGroup partitions bodies within worlds into different groups // for collision detection. 0 does not collide with anything. // Negative numbers are global within a world, except they don't // collide amongst themselves (all non-dynamic bodies should go // in -1 because they don't collide amongst each-other, but do // potentially collide with dynamics). // Positive numbers only collide amongst themselves, and with // negative groups, but not other positive groups. To avoid // unwanted collisions, put bodies into separate groups. // There is an automatic constraint that the two objects // within a single joint do not collide with each other, so this // does not need to be handled here. BodyGroup // BodyHSize is the half-size (e.g., radius) of the body. // Values depend on shape type: X is generally radius, // Y is half-height. BodyHSizeX BodyHSizeY BodyHSizeZ // BodyThick is the thickness of the body, as a hollow shape. // If 0, then it is a solid shape (default). BodyThick // BodyMass is the mass of the object. BodyMass // BodyInvMass is 1/mass of the object or 0 if no mass. BodyInvMass // BodyBounce specifies the COR or coefficient of restitution (0..1), // which determines how elastic the collision is, // i.e., final velocity / initial velocity. BodyBounce // BodyFriction is the standard coefficient for linear friction (mu). BodyFriction // BodyFrictionTortion is resistance to spinning at the contact point. BodyFrictionTortion // BodyFrictionRolling is resistance to rolling motion at contact. BodyFrictionRolling // 3D position of body (structural center). BodyPosX BodyPosY BodyPosZ // Quaternion rotation of body. BodyQuatX BodyQuatY BodyQuatZ BodyQuatW // Relative center-of-mass offset from 3D position of body. BodyComX BodyComY BodyComZ // Inertia 3x3 matrix (column matrix organization, r,c labels). BodyInertiaXX BodyInertiaYX BodyInertiaZX BodyInertiaXY BodyInertiaYY BodyInertiaZY BodyInertiaXZ BodyInertiaYZ BodyInertiaZZ // InvInertia inverse inertia 3x3 matrix (column matrix organization, r,c labels). BodyInvInertiaXX BodyInvInertiaYX BodyInvInertiaZX BodyInvInertiaXY BodyInvInertiaYY BodyInvInertiaZY BodyInvInertiaXZ BodyInvInertiaYZ BodyInvInertiaZZ // radius for broadphase collision BodyRadius )
const BodyVarsN BodyVars = 43
BodyVarsN is the highest valid value for type BodyVars, plus one.
func BodyVarsValues ¶
func BodyVarsValues() []BodyVars
BodyVarsValues returns all possible values for the type BodyVars.
func (BodyVars) MarshalText ¶
MarshalText implements the encoding.TextMarshaler interface.
func (*BodyVars) SetString ¶
SetString sets the BodyVars value from its string representation, and returns an error if the string is invalid.
func (*BodyVars) UnmarshalText ¶
UnmarshalText implements the encoding.TextUnmarshaler interface.
type ContactVars ¶
type ContactVars int32 //enums:enum
Contact is one pairwise point of contact between two bodies. Contacts are represented in spherical terms relative to the spherical BBox of A and B.
const ( // first body index ContactA ContactVars = iota // the other body index ContactB // contact point index for A-B pair ContactPointIdx // contact point on body A ContactAPointX ContactAPointY ContactAPointZ // contact point on body B ContactBPointX ContactBPointY ContactBPointZ // contact offset on body A ContactAOffX ContactAOffY ContactAOffZ // contact offset on body B ContactBOffX ContactBOffY ContactBOffZ // Contact thickness ContactAThick ContactBThick // normal pointing from center of B to center of A ContactNormX ContactNormY ContactNormZ // contact weighting -- 1 if contact made; for restitution // use this to filter contacts when updating body. ContactWeight // computed contact deltas, A ContactADeltaX ContactADeltaY ContactADeltaZ ContactAAngDeltaX ContactAAngDeltaY ContactAAngDeltaZ // computed contact deltas, B ContactBDeltaX ContactBDeltaY ContactBDeltaZ ContactBAngDeltaX ContactBAngDeltaY ContactBAngDeltaZ )
const ContactVarsN ContactVars = 33
ContactVarsN is the highest valid value for type ContactVars, plus one.
func ContactVarsValues ¶
func ContactVarsValues() []ContactVars
ContactVarsValues returns all possible values for the type ContactVars.
func (ContactVars) Desc ¶
func (i ContactVars) Desc() string
Desc returns the description of the ContactVars value.
func (ContactVars) Int64 ¶
func (i ContactVars) Int64() int64
Int64 returns the ContactVars value as an int64.
func (ContactVars) MarshalText ¶
func (i ContactVars) MarshalText() ([]byte, error)
MarshalText implements the encoding.TextMarshaler interface.
func (*ContactVars) SetInt64 ¶
func (i *ContactVars) SetInt64(in int64)
SetInt64 sets the ContactVars value from an int64.
func (*ContactVars) SetString ¶
func (i *ContactVars) SetString(s string) error
SetString sets the ContactVars value from its string representation, and returns an error if the string is invalid.
func (ContactVars) String ¶
func (i ContactVars) String() string
String returns the string representation of this ContactVars value.
func (*ContactVars) UnmarshalText ¶
func (i *ContactVars) UnmarshalText(text []byte) error
UnmarshalText implements the encoding.TextUnmarshaler interface.
func (ContactVars) Values ¶
func (i ContactVars) Values() []enums.Enum
Values returns all possible values for the type ContactVars.
type DynamicVars ¶
type DynamicVars int32 //enums:enum
DynamicVars are dynamic body variables stored in tensor.Float32.
const ( // Index of body in list of bodies. DynBody DynamicVars = iota // 3D position of structural center. DynPosX DynPosY DynPosZ // Quaternion rotation. DynQuatX DynQuatY DynQuatZ DynQuatW // Linear velocity. DynVelX DynVelY DynVelZ // Angular velocity. DynAngVelX DynAngVelY DynAngVelZ // Linear acceleration. DynAccX DynAccY DynAccZ // Angular acceleration due to applied torques. DynAngAccX DynAngAccY DynAngAccZ // Linear force driving linear acceleration (from joints, etc). DynForceX DynForceY DynForceZ // Torque driving angular acceleration (from joints, etc). DynTorqueX DynTorqueY DynTorqueZ // Linear deltas. These accumulate over time via StepBodyDeltas. DynDeltaX DynDeltaY DynDeltaZ // Angular deltas. These accumulate over time via StepBodyDeltas. DynAngDeltaX DynAngDeltaY DynAngDeltaZ // integrated weight of all contacts DynContactWeight )
const DynamicVarsN DynamicVars = 33
DynamicVarsN is the highest valid value for type DynamicVars, plus one.
func DynamicVarsValues ¶
func DynamicVarsValues() []DynamicVars
DynamicVarsValues returns all possible values for the type DynamicVars.
func (DynamicVars) Desc ¶
func (i DynamicVars) Desc() string
Desc returns the description of the DynamicVars value.
func (DynamicVars) Int64 ¶
func (i DynamicVars) Int64() int64
Int64 returns the DynamicVars value as an int64.
func (DynamicVars) MarshalText ¶
func (i DynamicVars) MarshalText() ([]byte, error)
MarshalText implements the encoding.TextMarshaler interface.
func (*DynamicVars) SetInt64 ¶
func (i *DynamicVars) SetInt64(in int64)
SetInt64 sets the DynamicVars value from an int64.
func (*DynamicVars) SetString ¶
func (i *DynamicVars) SetString(s string) error
SetString sets the DynamicVars value from its string representation, and returns an error if the string is invalid.
func (DynamicVars) String ¶
func (i DynamicVars) String() string
String returns the string representation of this DynamicVars value.
func (*DynamicVars) UnmarshalText ¶
func (i *DynamicVars) UnmarshalText(text []byte) error
UnmarshalText implements the encoding.TextUnmarshaler interface.
func (DynamicVars) Values ¶
func (i DynamicVars) Values() []enums.Enum
Values returns all possible values for the type DynamicVars.
type GPUVars ¶
type GPUVars int32 //enums:enum
GPUVars is an enum for GPU variables, for specifying what to sync.
const ( ParamsVar GPUVars = 0 BodiesVar GPUVars = 1 ObjectsVar GPUVars = 2 BodyJointsVar GPUVars = 3 JointsVar GPUVars = 4 JointDoFsVar GPUVars = 5 BodyCollidePairsVar GPUVars = 6 DynamicsVar GPUVars = 7 BroadContactsNVar GPUVars = 8 BroadContactsVar GPUVars = 9 ContactsNVar GPUVars = 10 ContactsVar GPUVars = 11 JointControlsVar GPUVars = 12 )
const GPUVarsN GPUVars = 13
GPUVarsN is the highest valid value for type GPUVars, plus one.
func GPUVarsValues ¶
func GPUVarsValues() []GPUVars
GPUVarsValues returns all possible values for the type GPUVars.
func (GPUVars) MarshalText ¶
MarshalText implements the encoding.TextMarshaler interface.
func (*GPUVars) SetString ¶
SetString sets the GPUVars value from its string representation, and returns an error if the string is invalid.
func (*GPUVars) UnmarshalText ¶
UnmarshalText implements the encoding.TextUnmarshaler interface.
type GeomData ¶
type GeomData struct {
BodyIdx int32
Shape Shapes
// MinSize is the min of the Size dimensions.
MinSize float32
// Thickness of shape.
Thick float32
// Radius is the effective radius for sphere-like elements (Sphere, Capsule, Cone)
Radius float32
Size math32.Vector3
// World-to-Body transform
// Position (R) (i.e., BodyPos)
WbR math32.Vector3
// Quaternion (Q) (i.e., BodyQuat)
WbQ math32.Quat
// Body-to-World transform (inverse)
// Position (R)
BwR math32.Vector3
// Quaternion (Q)
BwQ math32.Quat
}
GeomData contains all geometric data for narrow-phase collision.
func NewGeomData ¶
type JointControlVars ¶
type JointControlVars int32 //enums:enum
JointControlVars are external joint control input variables stored in tensor.Float32. These must be in one-to-one correspondence with the JointDoFs.
const ( // Joint force and torque inputs JointControlForce JointControlVars = iota // JointTargetPos is the position target value input to the model, // where 0 is the initial position. For angular joints, this is in radians. // This is subject to a graded transition over time, [JointTargetPosCur] // has the current effective value. JointTargetPos // JointTargetPosCur is the current position target value, // updated from [JointTargetPos] input using the [Params.ControlDt] // time constant. JointTargetPosCur // JointTargetStiff determines how strongly the target position // is enforced: 0 = not at all; larger = stronger (e.g., 1000 or higher). // Set to 0 to allow the joint to be fully flexible. JointTargetStiff // JointTargetVel is the velocity target value. For example, 0 // effectively damps joint movement in proportion to Damp parameter. JointTargetVel // JointTargetDamp determines how strongly the target velocity is enforced: // 0 = not at all; larger = stronger (e.g., 1 is reasonable). // Set to 0 to allow the joint to be fully flexible. JointTargetDamp )
const JointControlVarsN JointControlVars = 6
JointControlVarsN is the highest valid value for type JointControlVars, plus one.
func JointControlVarsValues ¶
func JointControlVarsValues() []JointControlVars
JointControlVarsValues returns all possible values for the type JointControlVars.
func (JointControlVars) Desc ¶
func (i JointControlVars) Desc() string
Desc returns the description of the JointControlVars value.
func (JointControlVars) Int64 ¶
func (i JointControlVars) Int64() int64
Int64 returns the JointControlVars value as an int64.
func (JointControlVars) MarshalText ¶
func (i JointControlVars) MarshalText() ([]byte, error)
MarshalText implements the encoding.TextMarshaler interface.
func (*JointControlVars) SetInt64 ¶
func (i *JointControlVars) SetInt64(in int64)
SetInt64 sets the JointControlVars value from an int64.
func (*JointControlVars) SetString ¶
func (i *JointControlVars) SetString(s string) error
SetString sets the JointControlVars value from its string representation, and returns an error if the string is invalid.
func (JointControlVars) String ¶
func (i JointControlVars) String() string
String returns the string representation of this JointControlVars value.
func (*JointControlVars) UnmarshalText ¶
func (i *JointControlVars) UnmarshalText(text []byte) error
UnmarshalText implements the encoding.TextUnmarshaler interface.
func (JointControlVars) Values ¶
func (i JointControlVars) Values() []enums.Enum
Values returns all possible values for the type JointControlVars.
type JointDoFVars ¶
type JointDoFVars int32 //enums:enum
JointDoFVars are joint DoF state variables stored in tensor.Float32, one for each DoF.
const ( // axis of articulation for the DoF JointAxisX JointDoFVars = iota JointAxisY JointAxisZ // joint limits JointLimitLower JointLimitUpper )
const JointDoFVarsN JointDoFVars = 5
JointDoFVarsN is the highest valid value for type JointDoFVars, plus one.
func JointDoFVarsValues ¶
func JointDoFVarsValues() []JointDoFVars
JointDoFVarsValues returns all possible values for the type JointDoFVars.
func (JointDoFVars) Desc ¶
func (i JointDoFVars) Desc() string
Desc returns the description of the JointDoFVars value.
func (JointDoFVars) Int64 ¶
func (i JointDoFVars) Int64() int64
Int64 returns the JointDoFVars value as an int64.
func (JointDoFVars) MarshalText ¶
func (i JointDoFVars) MarshalText() ([]byte, error)
MarshalText implements the encoding.TextMarshaler interface.
func (*JointDoFVars) SetInt64 ¶
func (i *JointDoFVars) SetInt64(in int64)
SetInt64 sets the JointDoFVars value from an int64.
func (*JointDoFVars) SetString ¶
func (i *JointDoFVars) SetString(s string) error
SetString sets the JointDoFVars value from its string representation, and returns an error if the string is invalid.
func (JointDoFVars) String ¶
func (i JointDoFVars) String() string
String returns the string representation of this JointDoFVars value.
func (*JointDoFVars) UnmarshalText ¶
func (i *JointDoFVars) UnmarshalText(text []byte) error
UnmarshalText implements the encoding.TextUnmarshaler interface.
func (JointDoFVars) Values ¶
func (i JointDoFVars) Values() []enums.Enum
Values returns all possible values for the type JointDoFVars.
type JointTypes ¶
type JointTypes int32 //enums:enum
JointTypes are joint types that determine nature of interaction.
const ( // Prismatic allows translation along a single axis (slider): 1 DoF. Prismatic JointTypes = iota // Revolute allows rotation about a single axis (axel): 1 DoF. Revolute // Ball allows rotation about all three axes (3 DoF, quaternion). Ball // Fixed locks all relative motion: 0 DoF. Fixed // Free allows full 6-DoF motion (translation and rotation). Free // Distance keeps two bodies a distance within joint limits: 6 DoF. Distance // D6 is a generic 6-DoF joint. D6 // PlaneXZ is a version of D6 for navigation in the X-Z plane, // which creates 2 linear DoF (X, Z) for movement. PlaneXZ )
const JointTypesN JointTypes = 8
JointTypesN is the highest valid value for type JointTypes, plus one.
func GetJointType ¶
func GetJointType(idx int32) JointTypes
func JointTypesValues ¶
func JointTypesValues() []JointTypes
JointTypesValues returns all possible values for the type JointTypes.
func (JointTypes) Desc ¶
func (i JointTypes) Desc() string
Desc returns the description of the JointTypes value.
func (JointTypes) Int64 ¶
func (i JointTypes) Int64() int64
Int64 returns the JointTypes value as an int64.
func (JointTypes) MarshalText ¶
func (i JointTypes) MarshalText() ([]byte, error)
MarshalText implements the encoding.TextMarshaler interface.
func (*JointTypes) SetInt64 ¶
func (i *JointTypes) SetInt64(in int64)
SetInt64 sets the JointTypes value from an int64.
func (*JointTypes) SetString ¶
func (i *JointTypes) SetString(s string) error
SetString sets the JointTypes value from its string representation, and returns an error if the string is invalid.
func (JointTypes) String ¶
func (i JointTypes) String() string
String returns the string representation of this JointTypes value.
func (*JointTypes) UnmarshalText ¶
func (i *JointTypes) UnmarshalText(text []byte) error
UnmarshalText implements the encoding.TextUnmarshaler interface.
func (JointTypes) Values ¶
func (i JointTypes) Values() []enums.Enum
Values returns all possible values for the type JointTypes.
type JointVars ¶
type JointVars int32 //enums:enum
JointVars are joint state variables stored in tensor.Float32. These are all static joint properties; dynamic control variables in JointControlVars and JointControls.
const ( // JointType (as an int32 from bits). JointType JointVars = iota // JointEnabled allows joints to be dynamically enabled. JointEnabled // JointParentFixed means that the parent is NOT updated based on // the forces and positions for this joint. This can make dynamics // cleaner when full accuracy is not necessary. JointParentFixed // JointNoLinearRotation ignores the rotational (angular) effects of // linear joint position constraints (i.e., Coriolis and centrifugal forces) // which can otherwise interfere with rotational position constraints in // joints with both linear and angular DoFs // (e.g., [PlaneXZ], for which this is on by default). JointNoLinearRotation // JointParent is the dynamic body index for parent body. // Can be -1 for a fixed parent for absolute anchor. JointParent // JointChild is the dynamic body index for child body. JointChild // relative position of joint, in parent frame. // This is prior to parent body rotation. JointPPosX JointPPosY JointPPosZ // relative orientation of joint, in parent frame. // This is prior to parent body rotation. JointPQuatX JointPQuatY JointPQuatZ JointPQuatW // relative position of joint, in child frame. // This is prior to child body rotation. JointCPosX JointCPosY JointCPosZ // relative orientation of joint, in child frame. // This is prior to parent body rotation. JointCQuatX JointCQuatY JointCQuatZ JointCQuatW // JointLinearDoFN is the number of linear degrees-of-freedom for the joint. JointLinearDoFN // JointAngularDoFN is the number of angular degrees-of-freedom for the joint. JointAngularDoFN // indexes in JointDoFs for each DoF JointDoF1 JointDoF2 JointDoF3 // angular starts here for Free, Distance, D6 JointDoF4 JointDoF5 JointDoF6 // Computed parent joint force value. JointPForceX JointPForceY JointPForceZ // Computed parent joint torque value. JointPTorqueX JointPTorqueY JointPTorqueZ // Computed child joint force value. JointCForceX JointCForceY JointCForceZ // Computed child joint torque value. JointCTorqueX JointCTorqueY JointCTorqueZ // Computed linear lambdas. JointLinLambdaX JointLinLambdaY JointLinLambdaZ // Computed angular lambdas. JointAngLambdaX JointAngLambdaY JointAngLambdaZ )
const JointVarsN JointVars = 46
JointVarsN is the highest valid value for type JointVars, plus one.
func JointVarsValues ¶
func JointVarsValues() []JointVars
JointVarsValues returns all possible values for the type JointVars.
func (JointVars) MarshalText ¶
MarshalText implements the encoding.TextMarshaler interface.
func (*JointVars) SetString ¶
SetString sets the JointVars value from its string representation, and returns an error if the string is invalid.
func (*JointVars) UnmarshalText ¶
UnmarshalText implements the encoding.TextUnmarshaler interface.
type Model ¶
type Model struct {
// GPU determines whether to use GPU (else CPU).
GPU bool
// Params are global parameters.
Params []PhysicsParams
// GetContacts will download Contacts from the GPU, if processing them on the CPU.
GetContacts bool
// ReportTotalKE prints out the total computed kinetic energy in the system after
// every step.
ReportTotalKE bool
// CurrentWorld is the [BodyWorld] value to use when creating new bodies.
// Set to -1 to create global elements that interact with everything,
// while 0 and positive numbers only interact amongst themselves.
CurrentWorld int
// CurrentObject is the Object to use when creating new joints.
// Call NewObject to increment.
CurrentObject int `edit:"-"`
// CurrentObjectJoint is the Joint index in CurrentObject
// to use when creating new joints.
CurrentObjectJoint int `edit:"-"`
// ReplicasN is the number of replicated worlds.
// Total bodies from ReplicasStart should be ReplicasN * ReplicaBodiesN.
ReplicasN int32 `edit:"-"`
// ReplicaBodiesStart is the starting body index for replicated world bodies,
// which is needed to efficiently select a body from a specific world.
// This is the start of the World=0 first instance.
ReplicaBodiesStart int32 `edit:"-"`
// ReplicaBodiesN is the number of body elements within each set of
// replicated world bodies, which is needed to efficiently select
// a body from a specific world.
ReplicaBodiesN int32 `edit:"-"`
// ReplicaJointsStart is the starting joint index for replicated world joints,
// which is needed to efficiently select a joint from a specific world.
// This is the start of the World=0 first instance.
ReplicaJointsStart int32 `edit:"-"`
// ReplicaJointsN is the number of joint elements within each set of
// replicated world joints, which is needed to efficiently select
// a joint from a specific world.
ReplicaJointsN int32 `edit:"-"`
// Bodies are the rigid body elements (dynamic and static),
// specifying the constant, non-dynamic properties,
// which is initial state for dynamics.
// [body][BodyVarsN]
Bodies *tensor.Float32 `display:"no-inline"`
// Objects is a list of joint indexes for each object, where each object
// contains all the joints interconnecting an overlapping set of bodies.
// This is known as an articulation in other physics software.
// Joints must be added in parent -> child order within objects, as joints
// are updated in sequential order within object.
// [object][MaxObjectJoints+1]
Objects *tensor.Int32 `display:"no-inline"`
// BodyJoints is a list of joint indexes for each dynamic body, for aggregating.
// [dyn body][parent, child][Params.BodyJointsMax]
BodyJoints *tensor.Int32 `display:"no-inline"`
// Joints is a list of permanent joints connecting bodies,
// which do not change (no dynamic variables).
// [joint][JointVarsN]
Joints *tensor.Float32 `display:"no-inline"`
// JointDoFs is a list of joint DoF parameters, allocated per joint.
// [dof][JointDoFVars]
JointDoFs *tensor.Float32 `display:"no-inline"`
// BodyCollidePairs are pairs of Body indexes that could potentially collide
// based on precomputed collision logic, using World, Group, and Joint indexes.
// [BodyCollidePairsN][2]
BodyCollidePairs *tensor.Int32
// Dynamics are the dynamic rigid body elements: these actually move.
// The first set of variables are for initial values, and the second current.
// [body][cur/next][DynamicVarsN]
Dynamics *tensor.Float32 `display:"no-inline"`
// BroadContactsN has number of points of broad contact
// between bodies. [1]
BroadContactsN *tensor.Int32 `display:"no-inline"`
// BroadContacts are the results of broad-phase contact processing,
// establishing possible points of contact between bodies.
// [ContactsMax][BroadContactVarsN]
BroadContacts *tensor.Float32 `display:"no-inline"`
// ContactsN has number of points of narrow (final) contact
// between bodies. [1]
ContactsN *tensor.Int32 `display:"no-inline"`
// Contacts are the results of narrow-phase contact processing,
// where only actual contacts with fully-specified values are present.
// [ContactsMax][ContactVarsN]
Contacts *tensor.Float32 `display:"no-inline"`
// JointControls are dynamic joint control inputs, per joint DoF
// (in correspondence with [JointDoFs]). This can be uploaded to the
// GPU at every step.
// [dof][JointControlVarsN]
JointControls *tensor.Float32 `display:"no-inline"`
}
Model contains and manages all of the physics elements.
func (*Model) Config ¶
func (ml *Model) Config()
Config does final configuration prior to running after everything has been added. Does SetAsCurrent, GPUInit.
func (*Model) ConfigBodies ¶
func (ml *Model) ConfigBodies()
ConfigBodies updates computed body values from current values. Call if body params (mass, size) change.
func (*Model) ConfigBodyCollidePairs ¶
func (ml *Model) ConfigBodyCollidePairs()
ConfigBodyCollidePairs compiles a list of body paris that could collide based on world and group settings and not being direct parent child relationship within a joint. Result has A with lower shape type, so that shapes are in a canonical order.
func (*Model) ConfigJoints ¶
func (ml *Model) ConfigJoints()
ConfigJoints does all of the initialization associated with joints.
func (*Model) GPUInit ¶
func (ml *Model) GPUInit()
GPUInit initializes the GPU and transfers Infra. Should have already called SetAsCurrent (needed for CPU and GPU).
func (*Model) Init ¶
func (ml *Model) Init()
Init makes initial vars. Called in NewModel. Must call Config once configured.
func (*Model) InitControlState ¶
func (ml *Model) InitControlState()
InitControlState initializes the JointTargetPosCur values to 0. This is done on the CPU prior to copying up to GPU, in InitState.
func (*Model) IsChildDynamic ¶
IsChildDynamic returns true if dic is a direct child on any joint where dip is the parent.
func (*Model) JointDefaults ¶
func (*Model) JointDoFDefaults ¶
func (*Model) NewBody ¶
NewBody adds a new body with given parameters. Returns the index. Use this for Static elements; NewDynamic for dynamic elements.
func (*Model) NewDynamic ¶
func (ml *Model) NewDynamic(shape Shapes, mass float32, hsize, pos math32.Vector3, rot math32.Quat) (bodyIdx, dynIdx int32)
NewDynamic adds a new dynamic body with given parameters. Returns the index. Shape cannot be Plane.
func (*Model) NewJointBall ¶
NewJointBall adds a new Ball joint (3 angular DoF) between parent and child dynamic object indexes. Use -1 for parent to add a world-anchored joint. ppos, cpos are the relative positions from the parent, child. Sets relative rotation matricies to identity by default.
func (*Model) NewJointD6 ¶
func (ml *Model) NewJointD6(parent, child int32, ppos, cpos math32.Vector3, linDoF, angDoF int32) int32
NewJointD6 adds a new D6 6 DoF joint with given number of actual linear and angular degrees-of-freedom, between parent and child dynamic object indexes. Use -1 for parent to add a world-anchored joint. ppos, cpos are the relative positions from the parent, child. Sets relative rotation matricies to identity by default.
func (*Model) NewJointDistance ¶
func (ml *Model) NewJointDistance(parent, child int32, ppos, cpos math32.Vector3, minDist, maxDist float32) int32
NewJointDistance adds a new Distance joint (6 DoF) between parent and child dynamic object indexes, with distance constrained only on the first linear X axis. Use -1 for parent to add a world-anchored joint. ppos, cpos are the relative positions from the parent, child. Sets relative rotation matricies to identity by default.
func (*Model) NewJointFixed ¶
NewJointFixed adds a new Fixed joint between parent and child dynamic object indexes. Use -1 for parent to add a world-anchored joint. ppos, cpos are the relative positions from the parent, child. Sets relative rotation matricies to identity by default.
func (*Model) NewJointFree ¶
NewJointFree adds a new Free joint (of which there is little point) between parent and child dynamic object indexes. Use -1 for parent to add a world-anchored joint. ppos, cpos are the relative positions from the parent, child. Sets relative rotation matricies to identity by default.
func (*Model) NewJointPlaneXZ ¶
NewJointPlaneXZ adds a new 3 DoF Planar motion joint suitable for controlling the motion of a body on the standard X-Z plane (Y = up). The two linear DoF control position in X, Z, and 3rd angular controls rotation in Y axis. Sets JointNoLinearRotation Use -1 for parent to add a world-anchored joint (typical). ppos, cpos are the relative positions from the parent, child. Sets relative rotation matricies to identity by default.
func (*Model) NewJointPrismatic ¶
NewJointPrismatic adds a new Prismatic (slider) joint between parent and child dynamic object indexes. Use -1 for parent to add a world-anchored joint. ppos, cpos are the relative positions from the parent, child. Sets relative rotation matricies to identity by default. axis is the axis of articulation for the joint.
func (*Model) NewJointRevolute ¶
NewJointRevolute adds a new Revolute (hinge, axel) joint between parent and child dynamic object indexes. Use -1 for parent to add a world-anchored joint. ppos, cpos are the relative positions from the parent, child. Sets relative rotation matricies to identity by default. axis is the axis of articulation for the joint.
func (*Model) ReplicasBodyIndexes ¶
ReplicasBodyIndexes returns the body and dynamics (if dynamic) indexes for given replica world and source body index, if ReplicasN is > 0. Otherwise, returns bi and corresponding dynamic index.
func (*Model) ReplicasJointIndex ¶
ReplicasJointIndex returns the joint indexe for given replica world and source body index, if ReplicasN is > 0. Otherwise, returns bi and corresponding dynamic index.
func (*Model) SetAsCurrent ¶
func (ml *Model) SetAsCurrent()
SetAsCurrent sets these as the current global values that are processed in the code (on the GPU). If this was not the setter of the current variables, then the parameter variables are copied up to the GPU.
func (*Model) SetAsCurrentVars ¶
func (ml *Model) SetAsCurrentVars()
SetAsCurrentVars sets these as the current global values that are processed in the code (on the GPU).
func (*Model) SetMass ¶
SetMass sets the mass of given body object (only relevant for dynamics), including a default inertia tensor based on solid shape of given size.
func (*Model) SetMaxContacts ¶
func (ml *Model) SetMaxContacts()
SetMaxContacts computes [Params.MaxContacts] based on current list of BodyCollidePairs.
func (*Model) Step ¶
func (ml *Model) Step()
Step runs one physics step, sending Params and JointControls to the GPU, and getting the Dynamics state vars back. Each step has SubSteps integration sub-steps.
func (*Model) StepBodyContacts ¶
func (ml *Model) StepBodyContacts()
func (*Model) StepCollision ¶
func (ml *Model) StepCollision()
func (*Model) StepIntegrateBodies ¶
func (ml *Model) StepIntegrateBodies()
func (*Model) StepJointForces ¶
func (ml *Model) StepJointForces()
func (*Model) StepSolveJoints ¶
func (ml *Model) StepSolveJoints()
func (*Model) ToGPUInfra ¶
func (ml *Model) ToGPUInfra()
ToGPUInfra copies all the infrastructure for these filters up to the GPU. This is done in GPUInit, and if current switched.
func (*Model) TotalKineticEnergy ¶
TotalKineticEnergy returns the total kinetic energy of the dynamic bodies, as a function of the velocities.
type PhysicsParams ¶
type PhysicsParams struct {
// Iterations is the number of integration iterations to perform
// within each solver step. Muller et al (2020) report that 1 is best.
Iterations int32 `default:"1"`
// Dt is the integration stepsize.
// For highly kinetic situations (e.g., rapidly moving bouncing balls)
// 0.0001 is needed to ensure contact registration. Use SubSteps to
// accomplish a target effective read-out step size.
Dt float32 `default:"0.0001"`
// SubSteps is the number of integration steps to take per Step()
// function call. These sub steps are taken without any sync to/from
// the GPU and are therefore much faster.
SubSteps int32 `default:"10" min:"1"`
// ControlDt is the stepsize for integrating joint control position values
// [JointTargetPos] over time, to avoid sudden strong changes in force.
// For higher-DoF joints (e.g., Ball), this can be important for stability,
// but it can also result in under-shoot of the target position.
ControlDt float32 `default:"1,0.1"`
// ControlDtThr is the threshold on the control delta above which
// ControlDt is used. ControlDt is most important for large changes,
// and can result in under-shoot if engaged for small changes.
ControlDtThr float32 `default:"1"`
// Contact margin is the extra distance for broadphase collision
// around rigid bodies. This can make some joints potentially unstable if > 0
ContactMargin float32 `default:"0,0.1"`
// ContactRelax is rigid contact relaxation constant.
// Higher values cause errros
ContactRelax float32 `default:"0.8"` // 0.8 def
// Contact weighting: balances contact forces?
ContactWeighting slbool.Bool `default:"true"` // true
// Restitution takes into account bounciness of objects.
Restitution slbool.Bool `default:"false"` // false
// JointLinearRelax is joint linear relaxation constant.
JointLinearRelax float32 `default:"0.7"` // 0.7 def
// JointAngularRelax is joint angular relaxation constant.
JointAngularRelax float32 `default:"0.4"` // 0.4 def
// JointLinearComply is joint linear compliance constant.
JointLinearComply float32 `default:"0"` // 0 def
// JointAngularComply is joint angular compliance constant.
JointAngularComply float32 `default:"0"` // 0 def
// AngularDamping is damping of angular motion.
AngularDamping float32 `default:"0"` // 0 def
// SoftRelax is soft-body relaxation constant.
SoftRelax float32 `default:"0.9"`
// MaxForce is the maximum computed force value, which prevents
// runaway numerical overflow.
MaxForce float32 `default:"1e5"`
// MaxDelta is the maximum computed change in position magnitude,
// which prevents runaway numerical overflow.
MaxDelta float32 `default:"2"`
// MaxGeomIter is number of iterations to perform in shape-based
// geometry collision computations
MaxGeomIter int32 `default:"10"`
// Maximum number of contacts to process at any given point.
ContactsMax int32 `edit:"-"`
// Index for the current state (0 or 1, alternates with Next).
Cur int32 `edit:"-"`
// Index for the next state (1 or 0, alternates with Cur).
Next int32 `edit:"-"`
// BodiesN is number of rigid bodies.
BodiesN int32 `edit:"-"`
// DynamicsN is number of dynamics bodies.
DynamicsN int32 `edit:"-"`
// ObjectsN is number of objects.
ObjectsN int32 `edit:"-"`
// MaxObjectJoints is max number of joints per object.
MaxObjectJoints int32 `edit:"-"`
// JointsN is number of joints.
JointsN int32 `edit:"-"`
// JointDoFsN is number of joint DoFs.
JointDoFsN int32 `edit:"-"`
// BodyJointsMax is max number of joints per body + 1 for actual n.
BodyJointsMax int32 `edit:"-"`
// BodyCollidePairsN is the total number of pre-compiled collision pairs
// to examine.
BodyCollidePairsN int32 `edit:"-"`
// Gravity is the gravity acceleration function
Gravity slvec.Vector3
// contains filtered or unexported fields
}
PhysicsParams are the physics parameters
func GetParams ¶
func GetParams(idx uint32) *PhysicsParams
GetParams returns a pointer to the given global variable: Params []PhysicsParams at given index. This directly processed in the GPU code, so this function call is an equivalent for the CPU.
func (*PhysicsParams) Defaults ¶
func (pr *PhysicsParams) Defaults()
func (*PhysicsParams) StepsToMsec ¶
func (pr *PhysicsParams) StepsToMsec(steps int) int
StepsToMsec returns the given number of individual Step calls converted into milliseconds, suitable for driving controls.
type Shapes ¶
type Shapes int32 //enums:enum
Shapes are elemental shapes for rigid bodies. In general, size dimensions are half values (e.g., radius, half-height, etc), which is natural for center-based body coordinates.
const ( // Plane cannot be a dynamic shape, but is most efficient for // collision computations. Use size = 0 for an infinite plane. // Natively extends in the X-Z plane: SizeX x SizeZ. Plane Shapes = iota // Sphere. SizeX is the radius. Sphere // Capsule is a cylinder with half-spheres on the ends. // Natively oriented vertically along the Y axis. // SizeX = radius of end caps, SizeY = _total_ half-height // (i.e., SizeX + half-height of cylindrical portion, must // be >= SizeX). This parameterization allows joint offsets // to be SizeY, and direct swapping of shape across Box and // Cylinder with same total extent. Capsule // Cylinder, natively oriented vertically along the Y axis. // SizeX = radius, SizeY = half-height of Y axis // Cylinder does not support most collisions and is thus not recommended // where collision data is needed. Cylinder // Box is a 3D rectalinear shape. // The sizes are _half_ sizes along each dimension, // relative to the center. Box // Cone is like a cylinder with the top radius = 0, // oriented up. SizeX = bottom radius, SizeY = half-height in Y. // Cone does not support any collisions and is not recommended for // interacting bodies. Cone )
const ShapesN Shapes = 6
ShapesN is the highest valid value for type Shapes, plus one.
func GetBodyShape ¶
func ShapesValues ¶
func ShapesValues() []Shapes
ShapesValues returns all possible values for the type Shapes.
func (Shapes) Inertia ¶
Inertia returns the inertia tensor for solid shape of given size, with uniform density and given mass.
func (Shapes) MarshalText ¶
MarshalText implements the encoding.TextMarshaler interface.
func (Shapes) Radius ¶
Radius returns the shape radius for given size. this is used for broad-phase collision.
func (*Shapes) SetString ¶
SetString sets the Shapes value from its string representation, and returns an error if the string is invalid.
func (*Shapes) UnmarshalText ¶
UnmarshalText implements the encoding.TextUnmarshaler interface.
Source Files
¶
Directories
¶
| Path | Synopsis |
|---|---|
|
Package builder provides a structured, hierarchical description of a physics.Model that supports replicating worlds for parallel world execution, and easier manipulation of objects as collections of bodies (e.g., an entire object can be moved and re-oriented in one call)..
|
Package builder provides a structured, hierarchical description of a physics.Model that supports replicating worlds for parallel world execution, and easier manipulation of objects as collections of bodies (e.g., an entire object can be moved and re-oriented in one call).. |
|
examples
|
|
|
balls/balls
command
|
|
|
collide/collide
command
|
|
|
pendula
command
|
|
|
virtroom/virtroom
command
|
|
|
package phyxyz implements visualization of physics using xyz 3D graphics.
|
package phyxyz implements visualization of physics using xyz 3D graphics. |