Index
All Classes and Interfaces|All Packages|Constant Field Values
A
- A - Enum constant in enum class com.jme3.bullet.joints.JointEnd
-
the first end
- AABB - Enum constant in enum class com.jme3.bullet.animation.CenterHeuristic
-
center of the smallest axis-aligned bounding box
- AABB - Enum constant in enum class com.jme3.bullet.animation.ShapeHeuristic
-
axis-aligned bounding box
- aabbCenter(Vector3f) - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Return the center of the shape's axis-aligned bounding box in local coordinates.
- aabbScaledVolume() - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Calculate a quick upper bound for the scaled volume of a shape, based on its axis-aligned bounding box.
- aabbVolume() - Method in class com.jme3.bullet.collision.shapes.HullCollisionShape
-
Calculate a quick upper bound for the unscaled volume of the hull, based on its axis-aligned bounding box.
- AbstractPhysicsControl - Class in com.jme3.bullet.control
-
Manage the lifecycle of a physics object linked to a Spatial in a scene graph.
- AbstractPhysicsControl() - Constructor for class com.jme3.bullet.control.AbstractPhysicsControl
-
Instantiate an enabled control that isn't added to any space or spatial.
- AbstractPhysicsDebugControl - Class in com.jme3.bullet.debug
-
The abstract base class for physics-debug controls (such as BulletRigidBodyDebugControl) used to visualize individual collision objects and joints.
- AbstractPhysicsDebugControl(BulletDebugAppState) - Constructor for class com.jme3.bullet.debug.AbstractPhysicsDebugControl
-
Instantiate an enabled Control to serve the specified debug app state.
- accelerate(float) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Apply the specified engine force to each wheel.
- accelerate(int, float) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Apply the specified engine force to the indexed wheel.
- ACDMode - Enum Class in vhacd
-
Enumerate the legal values for the m_mode field of IVHACD::Parameters.
- activate() - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Reactivate the body if it has been deactivated due to lack of motion.
- activate(boolean) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Reactivate the collision object if it has been deactivated due to lack of motion.
- activateAll(boolean) - Method in class com.jme3.bullet.MultiBodySpace
-
Activate all colliders and rigid bodies in this space.
- activateAll(boolean) - Method in class com.jme3.bullet.PhysicsSpace
-
Activate all rigid bodies in the space.
- Activation - Class in com.jme3.bullet.collision
-
Named activation states for use with a PhysicsCollisionObject.
- active - Static variable in class com.jme3.bullet.collision.Activation
-
an active collision object that's subject to deactivation when its timer runs out (native name: ACTIVE_TAG)
- add(IndexedMesh) - Method in class com.jme3.bullet.collision.shapes.infos.CompoundMesh
-
Add a submesh to this mesh.
- add(Object) - Method in class com.jme3.bullet.CollisionSpace
-
Add the specified object to the space.
- add(Object) - Method in class com.jme3.bullet.MultiBodySpace
-
Add the specified object to this space.
- add(Object) - Method in class com.jme3.bullet.PhysicsSpace
-
Add the specified object to the space.
- addAll(Spatial) - Method in class com.jme3.bullet.PhysicsSpace
-
Add all physics controls in the specified subtree of the scene graph to the space (e.g.
- addBaseCollider(CollisionShape) - Method in class com.jme3.bullet.MultiBody
-
Add a collider for the base.
- addBaseForce(Vector3f) - Method in class com.jme3.bullet.MultiBody
-
Add an external force to the base.
- addBaseTorque(Vector3f) - Method in class com.jme3.bullet.MultiBody
-
Add an external torque to the base.
- addChildShape(CollisionShape) - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Add a child shape without transforming its coordinates.
- addChildShape(CollisionShape, float, float, float) - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Add a child shape with the specified local translation.
- addChildShape(CollisionShape, Transform) - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Add a child shape with the specified local transform.
- addChildShape(CollisionShape, Vector3f) - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Add a child shape with the specified local translation.
- addChildShape(CollisionShape, Vector3f, Matrix3f) - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Add a child shape with the specified local translation and orientation.
- addCollider(CollisionShape) - Method in class com.jme3.bullet.MultiBodyLink
-
Add a collider for this link.
- addCollideWithGroup(int) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Add collision groups to the set with which this object can collide.
- addCollisionGroupListener(PhysicsCollisionGroupListener, int) - Method in class com.jme3.bullet.CollisionSpace
-
Register the specified collision-group listener with the specified collision group of the space.
- addCollisionListener(RagdollCollisionListener) - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Add a collision listener to this Control.
- addCollisionListener(PhysicsCollisionListener) - Method in interface com.jme3.bullet.ContactManager
-
Register the specified listener for new contacts.
- addCollisionListener(PhysicsCollisionListener) - Method in class com.jme3.bullet.DefaultContactManager
-
Register the specified listener for new contacts.
- addCollisionListener(PhysicsCollisionListener) - Method in class com.jme3.bullet.PhysicsSpace
-
Register the specified listener for new contacts.
- addCollisionObject(PhysicsCollisionObject) - Method in class com.jme3.bullet.CollisionSpace
-
Add the specified collision object to the space.
- addCollisionObject(PhysicsCollisionObject) - Method in class com.jme3.bullet.DeformableSpace
-
Add the specified collision object to this space.
- addCollisionObject(PhysicsCollisionObject) - Method in class com.jme3.bullet.PhysicsSoftSpace
-
Add the specified collision object to this space.
- addCollisionObject(PhysicsCollisionObject) - Method in class com.jme3.bullet.PhysicsSpace
-
Add the specified collision object to the space.
- addConstraintForce(Vector3f) - Method in class com.jme3.bullet.MultiBodyLink
-
Add an external force to this link.
- addConstraintTorque(Vector3f) - Method in class com.jme3.bullet.MultiBodyLink
-
Add an external torque to this link.
- addContactListener(ContactListener) - Method in class com.jme3.bullet.PhysicsSpace
-
Register the specified listener for immediate contact notifications.
- addContactListener(ContactListener, boolean, boolean, boolean) - Method in interface com.jme3.bullet.ContactManager
-
Register the specified listener for immediate contact notifications.
- addContactListener(ContactListener, boolean, boolean, boolean) - Method in class com.jme3.bullet.DefaultContactManager
-
Register the specified listener for immediate contact notifications.
- addContactListener(ContactListener, boolean, boolean, boolean) - Method in class com.jme3.bullet.PhysicsSpace
-
Register the specified listener for immediate contact notifications.
- added - Variable in class com.jme3.bullet.control.AbstractPhysicsControl
-
true→body is added to the PhysicsSpace, false→not added
- addException(Object) - Method in class jme3utilities.minie.FilterAll
-
Add an exceptional object to the list.
- addForce(Vector3f) - Method in class com.jme3.bullet.MultiBodyLink
-
Add an external force to this link.
- addIKController(IKController) - Method in class com.jme3.bullet.animation.PhysicsLink
-
Add an IK controller.
- addJoint(PhysicsJoint) - Method in class com.jme3.bullet.objects.PhysicsBody
-
Do not invoke directly! Joints are added automatically when created.
- addJoint(PhysicsJoint) - Method in class com.jme3.bullet.PhysicsSpace
-
Add the specified PhysicsJoint to the space.
- addJointTorque(int, float) - Method in class com.jme3.bullet.MultiBodyLink
-
Add an external torque to this link's joint.
- addMultiBody(MultiBody) - Method in class com.jme3.bullet.MultiBodySpace
-
Add the specified MultiBody and all its colliders.
- addOngoingCollisionListener(PhysicsCollisionListener) - Method in interface com.jme3.bullet.ContactManager
-
Register the specified listener for ongoing contacts.
- addOngoingCollisionListener(PhysicsCollisionListener) - Method in class com.jme3.bullet.DefaultContactManager
-
Register the specified listener for ongoing contacts.
- addOngoingCollisionListener(PhysicsCollisionListener) - Method in class com.jme3.bullet.PhysicsSpace
-
Register the specified listener for ongoing contacts.
- addPhysics() - Method in class com.jme3.bullet.animation.DacLinks
-
Add all managed physics objects to the PhysicsSpace.
- addPhysics() - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Add all managed physics objects to the PhysicsSpace.
- addPhysics() - Method in class com.jme3.bullet.control.AbstractPhysicsControl
-
Add all managed physics objects to the PhysicsSpace.
- addPhysics() - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Add all managed physics objects to the PhysicsSpace.
- addPhysics() - Method in class com.jme3.bullet.control.CharacterControl
-
Add all managed physics objects to the PhysicsSpace.
- addPhysics() - Method in class com.jme3.bullet.control.JoinedBodyControl
-
Add all managed physics objects to the PhysicsSpace.
- addPhysics() - Method in class com.jme3.bullet.control.SoftBodyControl
-
Add all managed physics objects to the PhysicsSpace.
- addProgressListener(VHACDProgressListener) - Static method in class vhacd.VHACD
-
Register the specified progress listener.
- addProgressListener(VHACDProgressListener) - Static method in class vhacd4.Vhacd4
-
Register the specified progress listener.
- addTickListener(PhysicsTickListener) - Method in class com.jme3.bullet.PhysicsSpace
-
Register the specified tick listener with the space.
- addToIgnoreList(PhysicsCollisionObject) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Add another collision object to this object's ignore list and vice versa.
- addTorque(Vector3f) - Method in class com.jme3.bullet.MultiBodyLink
-
Add an external torque to this link.
- addUnlinkedDescendants(Joint, Collection<Joint>) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Add unlinked descendants of the specified Joint to the specified collection.
- addUnlinkedDescendants(Bone, Collection<Bone>) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Add unlinked descendants of the specified Bone to the specified collection.
- addVelocity(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Add velocity to this entire body.
- addVelocity(Vector3f, int) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Add velocity to the indexed node of this body.
- addWheel(VehicleWheel, VehicleTuning) - Method in class com.jme3.bullet.objects.infos.VehicleController
-
Add a wheel to this controller.
- addWheel(Vector3f, Vector3f, Vector3f, float, float, boolean) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
For compatibility with the jme3-jbullet library.
- addWheel(Spatial, Vector3f, Vector3f, Vector3f, float, float, boolean) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Add a wheel to this vehicle.
- Aero - Enum Class in com.jme3.bullet.objects.infos
-
Enumerate the implemented aerodynamic models for a SoftBodyConfig.
- aerodynamics() - Method in class com.jme3.bullet.objects.infos.SoftBodyConfig
-
Return the aerodynamics model.
- AfMode - Class in com.jme3.bullet.collision
-
Named anisotropic friction modes for use with a PhysicsCollisionObject.
- airDensity() - Method in class com.jme3.bullet.SoftBodyWorldInfo
-
Return the air density.
- AllowZeroLength - Static variable in class com.jme3.bullet.SolverMode
-
allow zero-length friction directions
- Amputated - Enum constant in enum class com.jme3.bullet.animation.KinematicSubmode
-
amputated away
- amputateSubtree(BoneLink, float) - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Begin blending the specified BoneLink and all its descendants into an amputated state.
- Anchor - Class in com.jme3.bullet.joints
-
A PhysicsJoint to join a particular node of a soft body (A) to a rigid body (B), based on Bullet's btSoftBody::Anchor.
- Anchor() - Constructor for class com.jme3.bullet.joints.Anchor
-
No-argument constructor needed by SavableClassUtil.
- Anchor(PhysicsSoftBody, int, PhysicsRigidBody, Vector3f, boolean) - Constructor for class com.jme3.bullet.joints.Anchor
-
Instantiate an anchor with influence=1.
- AnchorHardness - Enum constant in enum class com.jme3.bullet.objects.infos.Sbcp
-
anchor hardness coefficient (≥0, ≤1, default=0.7, native field: kAHR)
- angularDamping() - Method in class com.jme3.bullet.MultiBody
-
Determine the angular damping.
- AngularDamping - Enum constant in enum class com.jme3.bullet.objects.infos.Cluster
-
angular damping coefficient (default=0, native field: m_adamping)
- angularStiffness() - Method in class com.jme3.bullet.objects.infos.SoftBodyMaterial
-
Read the angular-stiffness coefficient (native field: m_kAST).
- Animated - Enum constant in enum class com.jme3.bullet.animation.KinematicSubmode
-
driven by animation (if any)
- animateSubtree(PhysicsLink, float) - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Begin blending the specified link and all its descendants to kinematic animation.
- AppDataFilter - Class in jme3utilities.minie
-
A simple DebugAppStateFilter that selects physics objects associated with a specific application-data object.
- AppDataFilter(Object) - Constructor for class jme3utilities.minie.AppDataFilter
-
Instantiate a filter for the specified application-data object.
- appendFaces(IndexBuffer) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Append faces to this body.
- appendFromLineMesh(Mesh, PhysicsSoftBody) - Static method in class com.jme3.bullet.util.NativeSoftBodyUtil
-
Append the edges in the specified line-mode Mesh to the specified soft body.
- appendFromNativeMesh(IndexedMesh, PhysicsSoftBody) - Static method in class com.jme3.bullet.util.NativeSoftBodyUtil
-
Add the triangles and unique edges in the specified native mesh to the specified soft body.
- appendFromTriMesh(Mesh, PhysicsSoftBody) - Static method in class com.jme3.bullet.util.NativeSoftBodyUtil
-
Add the triangles and unique edges in the specified JME mesh to the specified soft body.
- appendLinks(IndexBuffer) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Append links to this body.
- appendNodes(FloatBuffer) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Append nodes to this body, each with mass=1.
- appendTetras(PhysicsSoftBody) - Static method in class com.jme3.bullet.util.NativeSoftBodyUtil
-
Append tetrahedra to the specified soft body, one per face, connecting its faces with the center of its axis-aligned bounding box.
- appendTetras(IndexBuffer) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Append tetrahedra to this body.
- appliedForce(Vector3f) - Method in class com.jme3.bullet.MultiBodyLink
-
Determine the net applied force on this link.
- appliedTorque(Vector3f) - Method in class com.jme3.bullet.MultiBodyLink
-
Determine the net applied torque on this link.
- applyAllExceptIgnoreListTo(PhysicsRigidBody) - Method in class com.jme3.bullet.objects.infos.RigidBodySnapshot
-
Apply all properties (except the ignore list) to the specified body.
- applyCentralForce(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Apply a force to the body's center of mass.
- applyCentralImpulse(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Apply an impulse to the body's center of mass.
- applyEngineForce(VehicleWheel, float) - Method in class com.jme3.bullet.objects.infos.VehicleController
-
Apply the specified engine force to the specified wheel.
- applyForce(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Apply a force that acts uniformly across the entire body.
- applyForce(Vector3f, int) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Apply a force to the indexed node of this body.
- applyForce(Vector3f, Vector3f) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Apply a force to the body.
- applyImpulse(Vector3f, Vector3f) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Apply an off-center impulse to the body.
- applyPhysicsTransform(Vector3f, Quaternion) - Method in class com.jme3.bullet.control.AbstractPhysicsControl
-
Apply a physics transform to the controlled Spatial.
- applyPhysicsTransform(Vector3f, Quaternion) - Method in class com.jme3.bullet.debug.AbstractPhysicsDebugControl
-
Apply the specified location and orientation to the controlled spatial.
- applyRotation(Quaternion) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Rotate this body.
- applyScale(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Scale this body.
- applyTo(PhysicsRigidBody) - Method in class com.jme3.bullet.objects.infos.RigidBodySnapshot
-
Apply the properties to the specified body.
- applyTorque(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Apply a torque to the body.
- applyTorqueImpulse(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Apply a torque impulse to the body.
- applyTransform(Transform) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Transform this body.
- applyTransform(Spatial) - Method in class com.jme3.bullet.objects.infos.RigidBodyMotionState
-
If the motion state has been updated, apply the new transform to the specified Spatial.
- applyTranslation(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Translate this body.
- applyWheelTransform() - Method in class com.jme3.bullet.objects.VehicleWheel
-
Apply this wheel's physics location and orientation to its visualization, if any.
- applyWheelTransforms() - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Used internally.
- aRadius() - Method in class com.jme3.bullet.collision.shapes.ConicalFrustum
-
Return the radius of the "A" base.
- arrowBlue - Variable in class com.jme3.bullet.debug.DebugTools
-
mesh for the blue arrow
- arrowBlueGeom - Variable in class com.jme3.bullet.debug.DebugTools
-
geometry for the blue arrow
- arrowGreen - Variable in class com.jme3.bullet.debug.DebugTools
-
mesh for the green arrow
- arrowGreenGeom - Variable in class com.jme3.bullet.debug.DebugTools
-
geometry for the green arrow
- arrowMagenta - Variable in class com.jme3.bullet.debug.DebugTools
-
mesh for the magenta arrow
- arrowMagentaGeom - Variable in class com.jme3.bullet.debug.DebugTools
-
geometry for the magenta arrow
- arrowPink - Variable in class com.jme3.bullet.debug.DebugTools
-
mesh for the pink arrow
- arrowPinkGeom - Variable in class com.jme3.bullet.debug.DebugTools
-
geometry for the pink arrow
- arrowRed - Variable in class com.jme3.bullet.debug.DebugTools
-
mesh for the red arrow
- arrowRedGeom - Variable in class com.jme3.bullet.debug.DebugTools
-
geometry for the red arrow
- arrowYellow - Variable in class com.jme3.bullet.debug.DebugTools
-
mesh for the yellow arrow
- arrowYellowGeom - Variable in class com.jme3.bullet.debug.DebugTools
-
geometry for the yellow arrow
- ArticulatedWarmStart - Static variable in class com.jme3.bullet.SolverMode
-
use articulated warm start
- attach(String, float, Spatial) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Configure the specified model as an attachment.
- attach(String, LinkConfig, Spatial) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Configure the specified model as an attachment.
- attachChild(Spatial) - Method in class com.jme3.bullet.debug.BulletDebugAppState
-
Attach the specified Spatial to the debug root node.
- attachCollisionShape(long, long) - Static method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Attach the identified
btCollisionShape
to the identifiedbtCollisionObject
. - attachmentConfig(String) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Access the configuration of the attachment link associated with the named bone.
- AttachmentLink - Class in com.jme3.bullet.animation
-
Link an attachments node to a jointed rigid body in a ragdoll.
- AttachmentLink() - Constructor for class com.jme3.bullet.animation.AttachmentLink
-
No-argument constructor needed by SavableClassUtil.
- attachmentMass(String) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Return the mass of the attachment associated with the named bone.
- attachmentMass(String) - Method in class com.jme3.bullet.animation.DacLinks
-
Return the mass of the attachment associated with the named bone.
- attachShape(CollisionShape) - Method in class com.jme3.bullet.objects.MultiBodyCollider
-
Attach the specified collision shape to this collider.
- axis(Vector3f) - Method in class com.jme3.bullet.MultiBodyLink
-
Determine the direction of the joint's axis for a planar, prismatic, or revolute joint.
- AXIS_SWEEP_3 - Enum constant in enum class com.jme3.bullet.PhysicsSpace.BroadphaseType
-
btAxisSweep3: incremental 3-D sweep and prune, requires world bounds, limited to 16_384 physics objects
- AXIS_SWEEP_3_32 - Enum constant in enum class com.jme3.bullet.PhysicsSpace.BroadphaseType
-
bt32BitAxisSweep3: incremental 3-D sweep and prune, requires world bounds, limited to 1_500_000 physics objects
- AXIS_X - Static variable in class com.jme3.bullet.PhysicsSpace
-
index of the X axis
- AXIS_Y - Static variable in class com.jme3.bullet.PhysicsSpace
-
index of the Y axis
- AXIS_Z - Static variable in class com.jme3.bullet.PhysicsSpace
-
index of the Z axis
- axisArrowLength() - Method in class com.jme3.bullet.debug.DebugConfiguration
-
Determine the length of axis arrows.
- axisLineWidth() - Method in class com.jme3.bullet.debug.DebugConfiguration
-
Determine the line width of axis arrows.
B
- B - Enum constant in enum class com.jme3.bullet.joints.JointEnd
-
the 2nd end
- baseAngularVelocity(Vector3f) - Method in class com.jme3.bullet.MultiBody
-
Determine the angular velocity of the base.
- baseForce(Vector3f) - Method in class com.jme3.bullet.MultiBody
-
Determine the net force on the base.
- baseInertia(Vector3f) - Method in class com.jme3.bullet.MultiBody
-
Determine the rotational inertia of the base.
- baseLocation(Vector3f) - Method in class com.jme3.bullet.MultiBody
-
Determine the location of the base's center of mass.
- baseMass() - Method in class com.jme3.bullet.MultiBody
-
Determine the mass of the base.
- baseOrientation(Quaternion) - Method in class com.jme3.bullet.MultiBody
-
Determine the orientation of the base.
- baseTorque(Vector3f) - Method in class com.jme3.bullet.MultiBody
-
Determine the net torque on the base.
- baseTransform(Transform) - Method in class com.jme3.bullet.MultiBody
-
Determine the transform of the base.
- baseVelocity(Vector3f) - Method in class com.jme3.bullet.MultiBody
-
Determine the linear velocity of the base's center of mass.
- basic - Static variable in class com.jme3.bullet.collision.AfMode
-
basic anisotropic friction mode (native name: CF_ANISOTROPIC_FRICTION)
- BetterCharacterControl - Class in com.jme3.bullet.control
-
This class is intended to replace the CharacterControl class.
- BetterCharacterControl() - Constructor for class com.jme3.bullet.control.BetterCharacterControl
-
No-argument constructor needed by SavableClassUtil.
- BetterCharacterControl(float, float, float) - Constructor for class com.jme3.bullet.control.BetterCharacterControl
-
Instantiate an enabled Control with the specified properties.
- bindSubtree(PhysicsLink, float) - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Begin blending the specified link and all its descendants into bind pose.
- blendToKinematicMode(float) - Method in class com.jme3.bullet.animation.PhysicsLink
-
Begin blending this link to a purely kinematic mode.
- blendToKinematicMode(float, Transform) - Method in class com.jme3.bullet.animation.AttachmentLink
-
Begin blending this link to a purely kinematic mode.
- blendToKinematicMode(float, Transform) - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Begin blending all links to purely kinematic mode, driven by animation.
- blendToKinematicMode(KinematicSubmode, float) - Method in class com.jme3.bullet.animation.BoneLink
-
Begin blending this link to a purely kinematic mode.
- blendToKinematicMode(KinematicSubmode, float, Transform) - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Begin blending all links to purely kinematic mode.
- blendToKinematicMode(KinematicSubmode, float, Transform) - Method in class com.jme3.bullet.animation.TorsoLink
-
Begin blending this link to a purely kinematic mode.
- boneIndex(int) - Method in class com.jme3.bullet.animation.BoneLink
-
Determine the index in the Armature/Skeleton of the indexed managed bone.
- boneIndex(int) - Method in class com.jme3.bullet.animation.TorsoLink
-
Determine the index in the Armature/Skeleton of the indexed managed bone.
- BoneLink - Class in com.jme3.bullet.animation
-
Link an animated bone in an Armature/Skeleton to a jointed rigid body in a ragdoll.
- BoneLink() - Constructor for class com.jme3.bullet.animation.BoneLink
-
No-argument constructor needed by SavableClassUtil.
- boneName() - Method in class com.jme3.bullet.animation.PhysicsLink
-
Read the name of the corresponding skeleton bone or armature joint.
- Bounce - Enum constant in enum class com.jme3.bullet.joints.motors.MotorParam
-
restitution/bounce factor at the limits (m_bounce, default=0)
- Bound - Enum constant in enum class com.jme3.bullet.animation.KinematicSubmode
-
forced into bind pose
- boundingBox(BoundingBox) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Calculate an axis-aligned bounding box for this object, based on its collision shape.
- boundingBox(BoundingBox) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Calculate the axis-aligned bounding box for this body.
- boundingBox(Vector3f, Matrix3f, BoundingBox) - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Calculate an axis-aligned bounding box with the specified translation and rotation applied.
- boundingBox(Vector3f, Quaternion, BoundingBox) - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Calculate an axis-aligned bounding box with the specified translation and rotation applied.
- BoundingValueHierarchy - Class in com.jme3.bullet.collision.shapes.infos
-
A Bounding-Value Hierarchy (BVH) generated for a MeshCollisionShape, based on Bullet's
btOptimizedBvh
. - BoundingValueHierarchy() - Constructor for class com.jme3.bullet.collision.shapes.infos.BoundingValueHierarchy
-
No-argument constructor needed by SavableClassUtil.
- BoundingValueHierarchy(byte[]) - Constructor for class com.jme3.bullet.collision.shapes.infos.BoundingValueHierarchy
-
Instantiate a (tracked) hierarchy from serialized bytes.
- BoundingValueHierarchy(MeshCollisionShape) - Constructor for class com.jme3.bullet.collision.shapes.infos.BoundingValueHierarchy
-
Instantiate an (untracked) reference to the hierarchy of the specified
MeshCollisionShape
. - BoundsInSpatials - Enum constant in enum class jme3utilities.minie.DumpFlags
-
world bounds in spatials
- Box2dShape - Class in com.jme3.bullet.collision.shapes
-
An axis-aligned, rectangular collision shape based on Bullet's
btBox2dShape
. - Box2dShape() - Constructor for class com.jme3.bullet.collision.shapes.Box2dShape
-
No-argument constructor needed by SavableClassUtil.
- Box2dShape(float) - Constructor for class com.jme3.bullet.collision.shapes.Box2dShape
-
Instantiate a square shape with the specified half extent.
- Box2dShape(float, float) - Constructor for class com.jme3.bullet.collision.shapes.Box2dShape
-
Instantiate a rectangle shape with the specified half extents.
- Box2dShape(Vector2f) - Constructor for class com.jme3.bullet.collision.shapes.Box2dShape
-
Instantiate a rectangle shape with the specified half extents.
- Box2dShape(Vector3f) - Constructor for class com.jme3.bullet.collision.shapes.Box2dShape
-
Instantiate a rectangle shape with the specified half extents.
- BoxCollisionShape - Class in com.jme3.bullet.collision.shapes
-
An axis-aligned, rectangular-solid collision shape based on Bullet's
btBoxShape
. - BoxCollisionShape() - Constructor for class com.jme3.bullet.collision.shapes.BoxCollisionShape
-
No-argument constructor needed by SavableClassUtil.
- BoxCollisionShape(float) - Constructor for class com.jme3.bullet.collision.shapes.BoxCollisionShape
-
Instantiate a cube shape with the specified half extent.
- BoxCollisionShape(float, float, float) - Constructor for class com.jme3.bullet.collision.shapes.BoxCollisionShape
-
Instantiate a box with the specified half extents.
- BoxCollisionShape(Vector3f) - Constructor for class com.jme3.bullet.collision.shapes.BoxCollisionShape
-
Instantiate a box with the specified half extents.
- BoxCollisionShape(FloatBuffer, int, int) - Constructor for class com.jme3.bullet.collision.shapes.BoxCollisionShape
-
Instantiate a box shape that encloses the sample locations in the specified FloatBuffer range.
- bRadius() - Method in class com.jme3.bullet.collision.shapes.ConicalFrustum
-
Return the radius of the "B" base.
- brake(float) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Apply the specified brake impulse to all wheels.
- brake(int, float) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Apply the specified brake impulse to the indexed wheel.
- brake(VehicleWheel, float) - Method in class com.jme3.bullet.objects.infos.VehicleController
-
Apply the specified brake impulse to the specified wheel.
- Buckets - Enum constant in enum class jme3utilities.minie.DumpFlags
-
render buckets in spatials
- BulletAppState - Class in com.jme3.bullet
-
An AppState to manage a single PhysicsSpace.
- BulletAppState() - Constructor for class com.jme3.bullet.BulletAppState
-
Instantiate an enabled app state to manage a new space with the DBVT broadphase collision-detection algorithm.
- BulletAppState(PhysicsSpace.BroadphaseType) - Constructor for class com.jme3.bullet.BulletAppState
-
Instantiate an enabled app state to manage a new PhysicsSpace.
- BulletAppState(Vector3f, Vector3f) - Constructor for class com.jme3.bullet.BulletAppState
-
Instantiate an enabled app state to manage a new space with the AXIS_SWEEP_3 broadphase collision-detection algorithm.
- BulletAppState(Vector3f, Vector3f, PhysicsSpace.BroadphaseType) - Constructor for class com.jme3.bullet.BulletAppState
-
Instantiate an enabled AppState to manage a new space.
- BulletAppState.ThreadingType - Enum Class in com.jme3.bullet
-
Enumerate threading modes.
- BulletCharacterDebugControl - Class in com.jme3.bullet.debug
-
A physics-debug control used to visualize a PhysicsCharacter.
- BulletCharacterDebugControl(BulletDebugAppState, PhysicsCharacter) - Constructor for class com.jme3.bullet.debug.BulletCharacterDebugControl
-
Instantiate an enabled control to visualize the specified character.
- BulletDebugAppState - Class in com.jme3.bullet.debug
-
An AppState to manage debug visualization of a PhysicsSpace.
- BulletDebugAppState(DebugConfiguration) - Constructor for class com.jme3.bullet.debug.BulletDebugAppState
-
Instantiate an AppState with the specified configuration.
- BulletDebugAppState.DebugAppStateFilter - Interface in com.jme3.bullet.debug
-
Interface to restrict which physics objects are visualized.
- bulletDebugInit(Node) - Method in interface com.jme3.bullet.debug.DebugInitListener
-
Callback from BulletDebugAppState, invoked just before the debug scene is added to the debug viewports.
- BulletGhostObjectDebugControl - Class in com.jme3.bullet.debug
-
A physics-debug control used to visualize a PhysicsGhostObject.
- BulletGhostObjectDebugControl(BulletDebugAppState, PhysicsGhostObject) - Constructor for class com.jme3.bullet.debug.BulletGhostObjectDebugControl
-
Instantiate an enabled control to visualize the specified ghost object.
- BulletRigidBodyDebugControl - Class in com.jme3.bullet.debug
-
A physics-debug control used to visualize a PhysicsRigidBody.
- BulletRigidBodyDebugControl(BulletDebugAppState, PhysicsRigidBody) - Constructor for class com.jme3.bullet.debug.BulletRigidBodyDebugControl
-
Instantiate an enabled control to visualize the specified body.
- BulletVehicleDebugControl - Class in com.jme3.bullet.debug
-
A physics-debug control used to visualize a PhysicsVehicle.
- BulletVehicleDebugControl(BulletDebugAppState, PhysicsVehicle) - Constructor for class com.jme3.bullet.debug.BulletVehicleDebugControl
-
Instantiate an enabled control to visualize the specified vehicle.
C
- CacheDirection - Static variable in class com.jme3.bullet.SolverMode
-
enable friction-direction caching
- CacheFriendly - Static variable in class com.jme3.bullet.SolverMode
-
cache friendly
- calculatedBasisA(Matrix3f) - Method in class com.jme3.bullet.joints.New6Dof
-
Calculate the pivot orientation of the A end.
- calculatedBasisB(Matrix3f) - Method in class com.jme3.bullet.joints.New6Dof
-
Calculate the pivot orientation of the B end.
- calculatedOriginA(Vector3f) - Method in class com.jme3.bullet.joints.New6Dof
-
Calculate the pivot location of the A end (native field: m_calculatedTransformA.m_origin).
- calculatedOriginB(Vector3f) - Method in class com.jme3.bullet.joints.New6Dof
-
Calculate the pivot location of the B end (native field: m_calculatedTransformB.m_origin).
- calculateNewForward(Quaternion, Vector3f, Vector3f) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Adjust the specified direction vector so it is perpendicular to the specified local "up" direction.
- canApplyPhysicsLocal(Control) - Static method in class jme3utilities.minie.MyControlP
-
Check whether a scene-graph control implements applyPhysicsLocal().
- canDisable(Control) - Static method in class jme3utilities.minie.MyControlP
-
Check whether a scene-graph control implements isEnabled() and setEnabled().
- canScale(Vector3f) - Method in class com.jme3.bullet.collision.shapes.CapsuleCollisionShape
-
Test whether the specified scale factors can be applied to the shape.
- canScale(Vector3f) - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Test whether the specified scale factors can be applied to the shape.
- canScale(Vector3f) - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Test whether the specified scale factors can be applied to this shape.
- canScale(Vector3f) - Method in class com.jme3.bullet.collision.shapes.ConeCollisionShape
-
Test whether the specified scale factors can be applied to this shape.
- canScale(Vector3f) - Method in class com.jme3.bullet.collision.shapes.ConicalFrustum
-
Test whether the specified scale factors can be applied to the shape.
- canScale(Vector3f) - Method in class com.jme3.bullet.collision.shapes.Convex2dShape
-
Test whether the specified scale factors can be applied to this shape.
- canScale(Vector3f) - Method in class com.jme3.bullet.collision.shapes.CylinderCollisionShape
-
Test whether the specified scale factors can be applied to this shape.
- canScale(Vector3f) - Method in class com.jme3.bullet.collision.shapes.MinkowskiSum
-
Test whether the specified scale factors can be applied to this shape.
- canScale(Vector3f) - Method in class com.jme3.bullet.collision.shapes.SimplexCollisionShape
-
Test whether the specified scale factors can be applied to the shape.
- canScale(Vector3f) - Method in class com.jme3.bullet.collision.shapes.SphereCollisionShape
-
Test whether the specified scale factors can be applied to the shape.
- canScale(Vector3f) - Method in class com.jme3.bullet.collision.shapes.SphericalSegment
-
Test whether the specified scale factors can be applied to the shape.
- canSet(float) - Method in enum class com.jme3.bullet.joints.motors.MotorParam
-
Test whether this parameter can be set to the specified value.
- canSet(float) - Method in enum class com.jme3.bullet.objects.infos.Cluster
-
Test whether this parameter can be set to the specified value.
- canSet(float) - Method in enum class com.jme3.bullet.objects.infos.Sbcp
-
Test whether this parameter can be set to the specified value.
- canSleep() - Method in class com.jme3.bullet.MultiBody
-
Test whether this MultiBody can sleep.
- canSplit() - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Test whether the shape can be split by an arbitrary plane.
- canSplit() - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Test whether this shape can be split by an arbitrary plane.
- canSplit() - Method in class com.jme3.bullet.collision.shapes.EmptyShape
-
Test whether the shape can be split by an arbitrary plane.
- canSplit() - Method in class com.jme3.bullet.collision.shapes.GImpactCollisionShape
-
Test whether the shape can be split by an arbitrary plane.
- canSplit() - Method in class com.jme3.bullet.collision.shapes.HullCollisionShape
-
Test whether the shape can be split by an arbitrary plane.
- canSplit() - Method in class com.jme3.bullet.collision.shapes.MeshCollisionShape
-
Test whether this shape can be split by an arbitrary plane.
- canWakeup() - Method in class com.jme3.bullet.MultiBody
-
Test whether this MultiBody can wake up.
- CapsuleCollisionShape - Class in com.jme3.bullet.collision.shapes
-
A capsule collision shape based on Bullet's
btCapsuleShapeX
,btCapsuleShape
, orbtCapsuleShapeZ
. - CapsuleCollisionShape() - Constructor for class com.jme3.bullet.collision.shapes.CapsuleCollisionShape
-
No-argument constructor needed by SavableClassUtil.
- CapsuleCollisionShape(float, float) - Constructor for class com.jme3.bullet.collision.shapes.CapsuleCollisionShape
-
Instantiate a Y-axis capsule shape with the specified radius and height.
- CapsuleCollisionShape(float, float, int) - Constructor for class com.jme3.bullet.collision.shapes.CapsuleCollisionShape
-
Instantiate a capsule shape around the specified main (height) axis.
- castRay(int) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Compute depth for the indexed wheel by raycasting.
- castRay(VehicleWheel) - Method in class com.jme3.bullet.objects.infos.VehicleController
-
Determine the depth for the specified wheel by raycasting.
- CcdFilter - Class in jme3utilities.minie
-
A simple DebugAppStateFilter that selects dynamic rigid bodies for which continuous collision detection (CCD) is active.
- CcdFilter() - Constructor for class jme3utilities.minie.CcdFilter
-
Instantiate a filter.
- center(VectorSet, Vector3f) - Method in enum class com.jme3.bullet.animation.CenterHeuristic
-
Calculate a center for the specified set of location vectors.
- centerHeuristic() - Method in class com.jme3.bullet.animation.LinkConfig
-
Read which centering heuristic to use.
- CenterHeuristic - Enum Class in com.jme3.bullet.animation
-
Enumerate algorithms to locate the center of mass for a PhysicsLink.
- centerOfMass(Vector3f, Vector3f) - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Calculate the ragdoll's total mass and center of mass, excluding released attachments.
- CHARACTER_OBJECT - Static variable in class com.jme3.bullet.collision.CollisionFlag
-
flag for a character object, such as a PhysicsCharacter
- CharacterControl - Class in com.jme3.bullet.control
-
A PhysicsControl to link a PhysicsCharacter to a Spatial.
- CharacterControl() - Constructor for class com.jme3.bullet.control.CharacterControl
-
No-argument constructor needed by SavableClassUtil.
- CharacterControl(ConvexShape, float) - Constructor for class com.jme3.bullet.control.CharacterControl
-
Instantiate an enabled Control with the specified CollisionShape and step height.
- CharacterController - Class in com.jme3.bullet.objects.infos
-
The "action" (controller) portion of a PhysicsCharacter, based on Bullet's btKinematicCharacterController.
- CharacterController() - Constructor for class com.jme3.bullet.objects.infos.CharacterController
-
No-argument constructor needed by SavableClassUtil.
- CharacterController(PhysicsCharacter) - Constructor for class com.jme3.bullet.objects.infos.CharacterController
-
Instantiate a controller for the specified collision object.
- checkCanUnDuck() - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Determine whether the character can emerge from the ducked state at its current location.
- checkOnGround() - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Update the internal
onGround
status. - checkParameters() - Method in class com.jme3.bullet.joints.SoftPhysicsJoint
-
Compare Bullet parameters against their local copies.
- checkRotationOrder() - Method in class com.jme3.bullet.joints.New6Dof
-
Compare Bullet's rotation order to the JVM copy.
- ChildCollisionShape - Class in com.jme3.bullet.collision.shapes.infos
-
An element in a CompoundCollisionShape, consisting of a (non-compound) base shape, offset and rotated with respect to its parent.
- ChildCollisionShape() - Constructor for class com.jme3.bullet.collision.shapes.infos.ChildCollisionShape
-
No-argument constructor needed by SavableClassUtil.
- ChildCollisionShape(Vector3f, CollisionShape) - Constructor for class com.jme3.bullet.collision.shapes.infos.ChildCollisionShape
-
Instantiate a child without any rotation.
- ChildCollisionShape(Vector3f, Matrix3f, CollisionShape) - Constructor for class com.jme3.bullet.collision.shapes.infos.ChildCollisionShape
-
Instantiate a child for use in a compound shape.
- ChildShapes - Enum constant in enum class jme3utilities.minie.DumpFlags
-
children in compound collision shapes
- CL_RS - Static variable in class com.jme3.bullet.objects.infos.ConfigFlag
-
enable the Cluster-versus-Convex handler for rigid-versus-soft collisions
- CL_SELF - Static variable in class com.jme3.bullet.objects.infos.ConfigFlag
-
enable self collisions for clusters
- CL_SS - Static variable in class com.jme3.bullet.objects.infos.ConfigFlag
-
enable the Cluster-versus-Cluster handler for soft-versus-soft collisions
- ClassFilter - Class in jme3utilities.minie
-
A simple DebugAppStateFilter to select objects that are assignable to a specific class.
- ClassFilter(Class<?>) - Constructor for class jme3utilities.minie.ClassFilter
-
Instantiate a filter for the specified class.
- cleanup() - Method in class com.jme3.bullet.BulletAppState
-
Transition this state from terminating to detached.
- cleanup(Application) - Method in class com.jme3.bullet.debug.BulletDebugAppState
-
Transition this state from terminating to detached.
- clearCache() - Static method in class com.jme3.bullet.util.DebugShapeFactory
-
Forget all previously generated debug meshes.
- clearConstraintForces() - Method in class com.jme3.bullet.MultiBody
-
Clear all constraint forces.
- clearExceptions() - Method in class jme3utilities.minie.FilterAll
-
Clear the list of exceptions.
- clearForces() - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Clear all forces and torques acting on the body, including gravity.
- clearForcesAndTorques() - Method in class com.jme3.bullet.MultiBody
-
Clear all external forces and torques.
- clearIgnoreList() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Clear this object's ignore list.
- clearVelocities() - Method in class com.jme3.bullet.MultiBody
-
Zero out all velocities.
- clone() - Method in class jme3utilities.minie.PhysicsDescriber
-
Create a copy of this PhysicsDescriber.
- clone() - Method in class jme3utilities.minie.PhysicsDumper
-
Create a deep copy of this dumper.
- clone() - Method in class vhacd.VHACDParameters
-
Create a copy of these parameters.
- clone() - Method in class vhacd4.Vhacd4Parameters
-
Create a copy of these parameters.
- cloneFields(Cloner, Object) - Method in class com.jme3.bullet.animation.AttachmentLink
-
Callback from
Cloner
to convert this shallow-cloned link into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.animation.BoneLink
-
Callback from
Cloner
to convert this shallow-cloned link into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Callback from
Cloner
to convert this shallow-cloned Control into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.animation.DacLinks
-
Callback from
Cloner
to convert this shallow-cloned Control into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Callback from
Cloner
to convert this shallow-cloned Control into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.animation.IKController
-
Callback from
Cloner
to convert this shallow-cloned controller into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.animation.IKJoint
-
Callback from
Cloner
to convert this shallow-cloned link into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.animation.PhysicsLink
-
Callback from
Cloner
to convert this shallow-cloned link into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.animation.PreComposer
-
Callback from
Cloner
to convert this shallow-cloned Control into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.animation.TorsoLink
-
Callback from
Cloner
to convert this shallow-cloned link into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Callback from
Cloner
to convert this shallow-cloned instance into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.collision.shapes.Box2dShape
-
Callback from
Cloner
to convert this shallow-cloned shape into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.collision.shapes.BoxCollisionShape
-
Callback from
Cloner
to convert this shallow-cloned shape into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.collision.shapes.CapsuleCollisionShape
-
Callback from
Cloner
to convert this shallow-cloned shape into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Callback from
Cloner
to convert this shallow-cloned shape into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Callback from
Cloner
to convert this shallow-cloned shape into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.collision.shapes.ConeCollisionShape
-
Callback from
Cloner
to convert this shallow-cloned shape into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.collision.shapes.ConicalFrustum
-
Callback from
Cloner
to convert this shallow-cloned shape into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.collision.shapes.Convex2dShape
-
Callback from
Cloner
to convert this shallow-cloned shape into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.collision.shapes.CustomConvexShape
-
Callback from
Cloner
to convert this shallow-cloned shape into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.collision.shapes.CylinderCollisionShape
-
Callback from
Cloner
to convert this shallow-cloned shape into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.collision.shapes.EmptyShape
-
Callback from
Cloner
to convert this shallow-cloned shape into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.collision.shapes.GImpactCollisionShape
-
Callback from
Cloner
to convert this shallow-cloned shape into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.collision.shapes.HeightfieldCollisionShape
-
Callback from
Cloner
to convert this shallow-cloned shape into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.collision.shapes.HullCollisionShape
-
Callback from
Cloner
to convert this shallow-cloned shape into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.collision.shapes.infos.BoundingValueHierarchy
-
Callback from
Cloner
to convert this shallow-cloned hierarchy into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.collision.shapes.infos.ChildCollisionShape
-
Callback from
Cloner
to convert this shallow-cloned element into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.collision.shapes.infos.CompoundMesh
-
Callback from
Cloner
to convert this shallow-cloned mesh into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.collision.shapes.infos.IndexedMesh
-
Callback from
Cloner
to convert this shallow-cloned mesh into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.collision.shapes.MeshCollisionShape
-
Callback from
Cloner
to convert this shallow-cloned shape into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.collision.shapes.MinkowskiSum
-
Callback from
Cloner
to convert this shallow-cloned shape into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.collision.shapes.MultiSphere
-
Callback from
Cloner
to convert this shallow-cloned shape into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.collision.shapes.PlaneCollisionShape
-
Callback from
Cloner
to convert this shallow-cloned shape into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.collision.shapes.SimplexCollisionShape
-
Callback from
Cloner
to convert this shallow-cloned shape into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.collision.shapes.SphereCollisionShape
-
Callback from
Cloner
to convert this shallow-cloned shape into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.collision.shapes.SphericalSegment
-
Callback from
Cloner
to convert this shallow-cloned shape into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.control.AbstractPhysicsControl
-
Callback from
Cloner
to convert this shallow-cloned Control into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Callback from
Cloner
to convert this shallow-cloned Control into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.control.CharacterControl
-
Callback from
Cloner
to convert this shallow-cloned Control into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.control.GhostControl
-
Callback from
Cloner
to convert this shallow-cloned Control into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.control.JoinedBodyControl
-
Callback from
Cloner
to convert this shallow-cloned Control into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.control.RigidBodyControl
-
Callback from
Cloner
to convert this shallow-cloned Control into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.control.SoftBodyControl
-
Callback from
Cloner
to convert this shallow-cloned Control into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.control.VehicleControl
-
Callback from
Cloner
to convert this shallow-cloned Control into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.debug.AbstractPhysicsDebugControl
-
Callback from
Cloner
to convert this shallow-cloned Control into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.joints.Anchor
-
Callback from
Cloner
to convert this shallow-cloned Anchor into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.joints.ConeJoint
-
Callback from
Cloner
to convert this shallow-cloned joint into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.joints.Constraint
-
Callback from
Cloner
to convert this shallow-cloned Constraint into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.joints.GearJoint
-
Callback from
Cloner
to convert this shallow-cloned joint into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.joints.HingeJoint
-
Callback from
Cloner
to convert this shallow-cloned object into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.joints.New6Dof
-
Callback from
Cloner
to convert this shallow-cloned constraint into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.joints.NewHinge
-
Callback from
Cloner
to convert this shallow-cloned constraint into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.joints.PhysicsJoint
-
Callback from
Cloner
to convert this shallow-cloned object into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.joints.Point2PointJoint
-
Callback from
Cloner
to convert this shallow-cloned joint into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.joints.SixDofJoint
-
Callback from
Cloner
to convert this shallow-cloned joint into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.joints.SixDofSpringJoint
-
Callback from
Cloner
to convert this shallow-cloned joint into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.joints.SliderJoint
-
Callback from
Cloner
to convert this shallow-cloned joint into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.joints.SoftAngularJoint
-
Callback from
Cloner
to convert this shallow-cloned joint into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.joints.SoftLinearJoint
-
Callback from
Cloner
to convert this shallow-cloned joint into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.MultiBody
-
Callback from
Cloner
to convert this shallow-cloned object into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.MultiBodyLink
-
Callback from
Cloner
to convert this shallow-cloned object into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Callback from
Cloner
to convert this shallow-cloned character into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.objects.infos.RigidBodyMotionState
-
Callback from
Cloner
to convert this shallow-cloned state into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.objects.infos.SoftBodyConfig
-
Callback from
Cloner
to convert this shallow-cloned config into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.objects.infos.SoftBodyMaterial
-
Callback from
Cloner
to convert this shallow-cloned material into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.objects.infos.VehicleTuning
-
Callback from
Cloner
to convert this shallow-cloned tuning into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.objects.MultiBodyCollider
-
Callback from
Cloner
to convert this shallow-cloned object into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.objects.PhysicsBody
-
Callback from
Cloner
to convert this shallow-cloned body into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Callback from
Cloner
to convert this shallow-cloned character into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.objects.PhysicsGhostObject
-
Callback from
Cloner
to convert this shallow-cloned object into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Callback from
Cloner
to convert this shallow-cloned body into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Callback from
Cloner
to convert this shallow-cloned body into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Callback from
Cloner
to convert this shallow-cloned body into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.objects.VehicleWheel
-
Callback from
Cloner
to convert this shallow-cloned wheel into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneFields(Cloner, Object) - Method in class com.jme3.bullet.SoftBodyWorldInfo
-
Callback from
Cloner
to convert this shallow-cloned info into a deep-cloned one, using the specified Cloner and original to resolve copied fields. - cloneForSpatial(Spatial) - Method in class com.jme3.bullet.control.AbstractPhysicsControl
-
Clone this Control for a different Spatial.
- cloneForSpatial(Spatial) - Method in class com.jme3.bullet.control.GhostControl
-
Clone this Control for a different Spatial.
- cloneForSpatial(Spatial) - Method in class com.jme3.bullet.control.RigidBodyControl
-
Clone this Control for a different Spatial.
- cloneForSpatial(Spatial) - Method in class com.jme3.bullet.control.VehicleControl
-
Clone this Control for a different Spatial.
- cloneIgnoreList(Cloner, PhysicsCollisionObject) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Clone the ignore list.
- cloneJoints(Cloner, PhysicsBody) - Method in class com.jme3.bullet.objects.PhysicsBody
-
Clone this body's joints.
- clonePositions() - Method in class vhacd.VHACDHull
-
Copy the vertex positions to a new array.
- clonePositions() - Method in class vhacd4.Vhacd4Hull
-
Copy the vertex positions to a new array.
- Cluster - Enum Class in com.jme3.bullet.objects.infos
-
Enumerate the float-valued parameters in a soft-body cluster.
- clusterCenter(int, Vector3f) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Copy the center location of the indexed cluster.
- clusterIndexA() - Method in class com.jme3.bullet.joints.SoftPhysicsJoint
-
Read the index of the cluster for the A end.
- clusterIndexB() - Method in class com.jme3.bullet.joints.SoftPhysicsJoint
-
Read the index of the cluster for the B end.
- clusterIterations() - Method in class com.jme3.bullet.objects.infos.SoftBodyConfig
-
Return the number of cluster-solver iterations (native field: citerations).
- ClusterKineticHardness - Enum constant in enum class com.jme3.bullet.objects.infos.Sbcp
-
cluster-versus-kinetic hardness coefficient (≥0, ≤1, default=1, native field: kSKHR_CL)
- ClusterKineticSplit - Enum constant in enum class com.jme3.bullet.objects.infos.Sbcp
-
cluster-versus-kinetic impulse-split coefficient (≥0, ≤1, default=0.5, native field: kSK_SPLT_CL)
- ClusterRigidHardness - Enum constant in enum class com.jme3.bullet.objects.infos.Sbcp
-
cluster-versus-rigidBody hardness coefficient (≥0, ≤1, default=0.1, native field: kSRHR_CL)
- ClusterRigidSplit - Enum constant in enum class com.jme3.bullet.objects.infos.Sbcp
-
cluster-versus-rigidBody impulse-split coefficient (≥0, ≤1, default=0.5, native field: kSR_SPLT_CL)
- ClustersInSofts - Enum constant in enum class jme3utilities.minie.DumpFlags
-
clusters in soft bodies
- ClusterSoftHardness - Enum constant in enum class com.jme3.bullet.objects.infos.Sbcp
-
cluster-versus-softBody hardness coefficient (≥0, ≤1, default=0.5, native field: kSSHR_CL)
- ClusterSoftSplit - Enum constant in enum class com.jme3.bullet.objects.infos.Sbcp
-
cluster-versus-softBody impulse-split coefficient (≥0, ≤1, default=0.5, native field: kSS_SPLT_CL).
- collide(PhysicsLink, PhysicsCollisionObject, PhysicsCollisionEvent) - Method in interface com.jme3.bullet.animation.RagdollCollisionListener
-
Invoked when a collision involving a linked rigid body occurs.
- collide(PhysicsCollisionObject, PhysicsCollisionObject) - Method in interface com.jme3.bullet.collision.PhysicsCollisionGroupListener
-
Invoked when a collision object in the registered group is about to collide.
- collider - Static variable in class com.jme3.bullet.collision.PcoType
-
value for a MultiBodyCollider (native name: CO_FEATHERSTONE_LINK)
- collideWithGroups() - Method in class com.jme3.bullet.MultiBody
-
Return the set of collision groups with which this multibody can collide.
- collision(PhysicsCollisionEvent) - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
For internal use only: callback for collision events.
- collision(PhysicsCollisionEvent) - Method in interface com.jme3.bullet.collision.PhysicsCollisionListener
-
Callback to report collisions in a CollisionSpace.
- COLLISION_GROUP_01 - Static variable in class com.jme3.bullet.collision.PhysicsCollisionObject
-
collisionGroup/collideWithGroups bitmask that represents group #1
- COLLISION_GROUP_02 - Static variable in class com.jme3.bullet.collision.PhysicsCollisionObject
-
collisionGroup/collideWithGroups bitmask that represents group #2
- COLLISION_GROUP_03 - Static variable in class com.jme3.bullet.collision.PhysicsCollisionObject
-
collisionGroup/collideWithGroups bitmask that represents group #3
- COLLISION_GROUP_04 - Static variable in class com.jme3.bullet.collision.PhysicsCollisionObject
-
collisionGroup/collideWithGroups bitmask that represents group #4
- COLLISION_GROUP_05 - Static variable in class com.jme3.bullet.collision.PhysicsCollisionObject
-
collisionGroup/collideWithGroups bitmask that represents group #5
- COLLISION_GROUP_06 - Static variable in class com.jme3.bullet.collision.PhysicsCollisionObject
-
collisionGroup/collideWithGroups bitmask that represents group #6
- COLLISION_GROUP_07 - Static variable in class com.jme3.bullet.collision.PhysicsCollisionObject
-
collisionGroup/collideWithGroups bitmask that represents group #7
- COLLISION_GROUP_08 - Static variable in class com.jme3.bullet.collision.PhysicsCollisionObject
-
collisionGroup/collideWithGroups bitmask that represents group #8
- COLLISION_GROUP_09 - Static variable in class com.jme3.bullet.collision.PhysicsCollisionObject
-
collisionGroup/collideWithGroups bitmask that represents group #9
- COLLISION_GROUP_10 - Static variable in class com.jme3.bullet.collision.PhysicsCollisionObject
-
collisionGroup/collideWithGroups bitmask that represents group #10
- COLLISION_GROUP_11 - Static variable in class com.jme3.bullet.collision.PhysicsCollisionObject
-
collisionGroup/collideWithGroups bitmask that represents group #11
- COLLISION_GROUP_12 - Static variable in class com.jme3.bullet.collision.PhysicsCollisionObject
-
collisionGroup/collideWithGroups bitmask that represents group #12
- COLLISION_GROUP_13 - Static variable in class com.jme3.bullet.collision.PhysicsCollisionObject
-
collisionGroup/collideWithGroups bitmask that represents group #13
- COLLISION_GROUP_14 - Static variable in class com.jme3.bullet.collision.PhysicsCollisionObject
-
collisionGroup/collideWithGroups bitmask that represents group #14
- COLLISION_GROUP_15 - Static variable in class com.jme3.bullet.collision.PhysicsCollisionObject
-
collisionGroup/collideWithGroups bitmask that represents group #15
- COLLISION_GROUP_16 - Static variable in class com.jme3.bullet.collision.PhysicsCollisionObject
-
collisionGroup/collideWithGroups bitmask that represents group #16
- COLLISION_GROUP_NONE - Static variable in class com.jme3.bullet.collision.PhysicsCollisionObject
-
collideWithGroups bitmask that represents "no groups"
- CollisionConfiguration - Class in com.jme3.bullet
-
Tuning parameters for a CollisionSpace, based on Bullet's btDefaultCollisionConstructionInfo.
- CollisionConfiguration() - Constructor for class com.jme3.bullet.CollisionConfiguration
-
Instantiate an instance with the default parameter values.
- CollisionConfiguration(int, int) - Constructor for class com.jme3.bullet.CollisionConfiguration
-
Instantiate an instance with the specified parameter values.
- CollisionFlag - Class in com.jme3.bullet.collision
-
Named collision flags for a PhysicsCollisionObject.
- collisionFlags() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Return the collision flags.
- collisionFlags() - Method in class com.jme3.bullet.objects.infos.SoftBodyConfig
-
Return the collisions flags (native field: collisions).
- collisionGroup() - Method in class com.jme3.bullet.MultiBody
-
Return the collision group of this multibody.
- CollisionShape - Class in com.jme3.bullet.collision.shapes
-
The abstract base class for collision shapes based on Bullet's
btCollisionShape
. - CollisionShape() - Constructor for class com.jme3.bullet.collision.shapes.CollisionShape
-
Instantiate a collision shape with no tracker and no assigned native object.
- CollisionShapeFactory - Class in com.jme3.bullet.util
-
Utility methods for generating collision shapes from models.
- CollisionSpace - Class in com.jme3.bullet
-
A Bullet-JME collision space with its own
btCollisionWorld
. - CollisionSpace(Vector3f, Vector3f, PhysicsSpace.BroadphaseType) - Constructor for class com.jme3.bullet.CollisionSpace
-
Instantiate a CollisionSpace.
- CollisionSpace(Vector3f, Vector3f, PhysicsSpace.BroadphaseType, int) - Constructor for class com.jme3.bullet.CollisionSpace
-
Used internally.
- CollisionSpace(Vector3f, Vector3f, PhysicsSpace.BroadphaseType, int, CollisionConfiguration) - Constructor for class com.jme3.bullet.CollisionSpace
-
Used internally.
- colorChildren() - Method in class com.jme3.bullet.debug.BulletCharacterDebugControl
-
Color each child of the debug node for a CompoundCollisionShape.
- com.jme3.bullet - package com.jme3.bullet
-
PhysicsSpace and some associated classes and interfaces.
- com.jme3.bullet.animation - package com.jme3.bullet.animation
-
A dynamic animation control and some associated classes.
- com.jme3.bullet.collision - package com.jme3.bullet.collision
-
Classes and interfaces associated with physics-oriented collision detection and ray/sweep tests.
- com.jme3.bullet.collision.shapes - package com.jme3.bullet.collision.shapes
-
Collision shapes, used to describe the shapes of Bullet collision objects other than soft bodies.
- com.jme3.bullet.collision.shapes.infos - package com.jme3.bullet.collision.shapes.infos
-
Auxiliary classes that relate to collision shapes.
- com.jme3.bullet.control - package com.jme3.bullet.control
-
Physics controls, used to link Bullet collision objects to particular spatials in a jMonkeyEngine scene graph.
- com.jme3.bullet.debug - package com.jme3.bullet.debug
-
Visualize physics objects for debugging.
- com.jme3.bullet.joints - package com.jme3.bullet.joints
-
Physics joints based on Bullet's btTypedConstraint.
- com.jme3.bullet.joints.motors - package com.jme3.bullet.joints.motors
-
Classes that provide access to the motors in a SixDofJoint or New6Dof.
- com.jme3.bullet.objects - package com.jme3.bullet.objects
-
Collision-object classes.
- com.jme3.bullet.objects.infos - package com.jme3.bullet.objects.infos
-
Auxiliary classes that relate to collision objects.
- com.jme3.bullet.util - package com.jme3.bullet.util
-
Utility classes for Bullet physics and related classes.
- compareTo(LinkConfig) - Method in class com.jme3.bullet.animation.LinkConfig
-
Compare with another LinkConfig object.
- compareTo(NativePhysicsObject) - Method in class com.jme3.bullet.NativePhysicsObject
-
Compare (by ID) with another native object.
- CompletionListener<T> - Interface in com.jme3.bullet.animation
-
Report the completion of an operation.
- CompoundCollisionShape - Class in com.jme3.bullet.collision.shapes
-
A collision shape formed by combining child shapes, based on Bullet's
btCompoundShape
. - CompoundCollisionShape() - Constructor for class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Instantiate an empty compound shape (with an initial capacity of 6, dynamic AABB, and no children).
- CompoundCollisionShape(int) - Constructor for class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Instantiate an empty compound shape with the specified initial capacity (and dynamic AABB and no children).
- CompoundMesh - Class in com.jme3.bullet.collision.shapes.infos
-
A scalable mesh that combines multiple indexed meshes.
- CompoundMesh() - Constructor for class com.jme3.bullet.collision.shapes.infos.CompoundMesh
-
Instantiate an empty mesh.
- CompoundMesh(CompoundMesh) - Constructor for class com.jme3.bullet.collision.shapes.infos.CompoundMesh
-
Copy an existing mesh.
- CompoundMesh(CompoundMesh, Vector3f) - Constructor for class com.jme3.bullet.collision.shapes.infos.CompoundMesh
-
Instantiate a mesh by applying an offset to an existing mesh.
- CompoundMesh(Mesh...) - Constructor for class com.jme3.bullet.collision.shapes.infos.CompoundMesh
-
Instantiate a mesh based on the specified JME mesh(es).
- compute(float[], int[], VHACDParameters) - Static method in class vhacd.VHACD
-
Generate convex hulls to approximate the specified mesh.
- compute(float[], int[], Vhacd4Parameters) - Static method in class vhacd4.Vhacd4
-
Generate convex hulls to approximate the specified mesh.
- ConeCollisionShape - Class in com.jme3.bullet.collision.shapes
-
A conical collision shape based on Bullet's
btConeShapeX
,btConeShape
, orbtConeShapeZ
. - ConeCollisionShape() - Constructor for class com.jme3.bullet.collision.shapes.ConeCollisionShape
-
No-argument constructor needed by SavableClassUtil.
- ConeCollisionShape(float, float) - Constructor for class com.jme3.bullet.collision.shapes.ConeCollisionShape
-
Instantiate a cone shape, oriented along the local Y axis.
- ConeCollisionShape(float, float, int) - Constructor for class com.jme3.bullet.collision.shapes.ConeCollisionShape
-
Instantiate a cone shape around the specified main (height) axis.
- ConeJoint - Class in com.jme3.bullet.joints
-
A 3 degree-of-freedom joint based on Bullet's btConeTwistConstraint.
- ConeJoint() - Constructor for class com.jme3.bullet.joints.ConeJoint
-
No-argument constructor needed by SavableClassUtil.
- ConeJoint(PhysicsRigidBody, PhysicsRigidBody, Vector3f, Vector3f) - Constructor for class com.jme3.bullet.joints.ConeJoint
-
Instantiate a double-ended ConeJoint.
- ConeJoint(PhysicsRigidBody, PhysicsRigidBody, Vector3f, Vector3f, Matrix3f, Matrix3f) - Constructor for class com.jme3.bullet.joints.ConeJoint
-
Instantiate a double-ended ConeJoint.
- ConeJoint(PhysicsRigidBody, Vector3f, Matrix3f) - Constructor for class com.jme3.bullet.joints.ConeJoint
-
Instantiate a single-ended ConeJoint with its pivot at the physics-space origin.
- config(String) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Access the configuration of the named bone/torso.
- ConfigFlag - Class in com.jme3.bullet.objects.infos
-
Named collision flags for use with a SoftBodyConfig.
- configureFixedLink(float, Vector3f, MultiBodyLink, Quaternion, Vector3f, Vector3f) - Method in class com.jme3.bullet.MultiBody
-
Configure a new link that is fixed to its parent.
- configurePlanarLink(float, Vector3f, MultiBodyLink, Quaternion, Vector3f, Vector3f, boolean) - Method in class com.jme3.bullet.MultiBody
-
Configure a link that is joined to its parent with a planar joint.
- configurePrismaticLink(float, Vector3f, MultiBodyLink, Quaternion, Vector3f, Vector3f, Vector3f, boolean) - Method in class com.jme3.bullet.MultiBody
-
Configure a link that is joined to its parent with a prismatic joint.
- configureRevoluteLink(float, Vector3f, MultiBodyLink, Quaternion, Vector3f, Vector3f, Vector3f, boolean) - Method in class com.jme3.bullet.MultiBody
-
Configure a link that is joined to its parent with a revolute joint.
- configureSphericalLink(float, Vector3f, MultiBodyLink, Quaternion, Vector3f, Vector3f, boolean) - Method in class com.jme3.bullet.MultiBody
-
Configure a link that is joined to its parent with a spherical joint.
- ConicalFrustum - Class in com.jme3.bullet.collision.shapes
-
A collision shape for a conical frustum with uniform density, based on
btConvexInternalShape
. - ConicalFrustum() - Constructor for class com.jme3.bullet.collision.shapes.ConicalFrustum
-
No-argument constructor needed by SavableClassUtil.
- ConicalFrustum(float, float, float) - Constructor for class com.jme3.bullet.collision.shapes.ConicalFrustum
-
Instantiate a conical frustum with the specified dimensions.
- connectivityMatrix(CollisionSpace) - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Generate a connectivity matrix for the children.
- Constraint - Class in com.jme3.bullet.joints
-
The abstract base class for rigid-body physics joints based on Bullet's btTypedConstraint.
- Constraint() - Constructor for class com.jme3.bullet.joints.Constraint
-
No-argument constructor needed by SavableClassUtil.
- Constraint(PhysicsBody, PhysicsBody, Vector3f, Vector3f) - Constructor for class com.jme3.bullet.joints.Constraint
-
Instantiate an enabled, double-ended Constraint.
- Constraint(PhysicsRigidBody, JointEnd, Vector3f) - Constructor for class com.jme3.bullet.joints.Constraint
-
Instantiate an enabled, single-ended Constraint using the specified body at the specified end.
- Constraint(PhysicsRigidBody, JointEnd, Vector3f, Vector3f) - Constructor for class com.jme3.bullet.joints.Constraint
-
Instantiate an enabled, single-ended Constraint using the specified body at the specified end.
- constraintForce(Vector3f) - Method in class com.jme3.bullet.MultiBodyLink
-
Determine the net constraint force on this link.
- constraintTorque(Vector3f) - Method in class com.jme3.bullet.MultiBodyLink
-
Determine the net constraint torque on this link.
- CONTACT_STIFFNESS_DAMPING - Static variable in class com.jme3.bullet.collision.ContactPointFlag
-
contact has stiffness damping
- contactErp() - Method in class com.jme3.bullet.SolverInfo
-
Return the error-reduction parameter for contact constraints (native field: m_erp2).
- ContactListener - Interface in com.jme3.bullet.collision
-
Interface to receive immediate notifications when 2 collision objects come into contact.
- ContactManager - Interface in com.jme3.bullet
-
Manage notifications when collision objects in a specific PhysicsSpace come into contact.
- ContactPointFlag - Class in com.jme3.bullet.collision
-
Named flags for a PhysicsCollisionEvent.
- contactTest(PhysicsCollisionObject, PhysicsCollisionListener) - Method in class com.jme3.bullet.CollisionSpace
-
Perform a contact test.
- contains(PhysicsCollisionObject) - Method in class com.jme3.bullet.CollisionSpace
-
Test whether the specified collision object is added to the space.
- contains(PhysicsCollisionObject) - Method in class com.jme3.bullet.DeformableSpace
-
Test whether the specified collision object is added to this space.
- contains(PhysicsCollisionObject) - Method in class com.jme3.bullet.MultiBodySpace
-
Test whether the specified collision object is added to this space.
- contains(PhysicsCollisionObject) - Method in class com.jme3.bullet.PhysicsSoftSpace
-
Test whether the specified collision object is added to this space.
- contains(PhysicsCollisionObject) - Method in class com.jme3.bullet.PhysicsSpace
-
Test whether the specified collision object is added to the space.
- contains(PhysicsJoint) - Method in class com.jme3.bullet.PhysicsSpace
-
Test whether the specified PhysicsJoint is added to the space.
- contains(MultiBodyCollider) - Method in class com.jme3.bullet.MultiBody
-
Test whether the specified collider is part of this MultiBody.
- controlRender(RenderManager, ViewPort) - Method in class com.jme3.bullet.animation.PreComposer
-
Render this Control.
- controlRender(RenderManager, ViewPort) - Method in class com.jme3.bullet.debug.AbstractPhysicsDebugControl
-
Render this Control.
- controlUpdate(float) - Method in class com.jme3.bullet.animation.PreComposer
-
Update this control.
- controlUpdate(float) - Method in class com.jme3.bullet.debug.BulletCharacterDebugControl
-
Update this control.
- controlUpdate(float) - Method in class com.jme3.bullet.debug.BulletGhostObjectDebugControl
-
Update this control.
- controlUpdate(float) - Method in class com.jme3.bullet.debug.BulletRigidBodyDebugControl
-
Update this control.
- controlUpdate(float) - Method in class com.jme3.bullet.debug.BulletVehicleDebugControl
-
Update this control.
- Convex2dShape - Class in com.jme3.bullet.collision.shapes
-
A convex collision shape optimized for 2-D, based on Bullet's
btConvex2dShape
. - Convex2dShape() - Constructor for class com.jme3.bullet.collision.shapes.Convex2dShape
-
No-argument constructor needed by SavableClassUtil.
- Convex2dShape(ConvexShape) - Constructor for class com.jme3.bullet.collision.shapes.Convex2dShape
-
Instantiate a shape based on the specified convex shape.
- Convex2dShape(FloatBuffer) - Constructor for class com.jme3.bullet.collision.shapes.Convex2dShape
-
Instantiate a 2-D hull shape based on a flipped buffer containing coordinates.
- ConvexShape - Class in com.jme3.bullet.collision.shapes
-
The abstract base class for convex collision shapes based on Bullet's
btConvexShape
. - ConvexShape() - Constructor for class com.jme3.bullet.collision.shapes.ConvexShape
-
Instantiate a collision shape with no tracker and no assigned native object.
- coordsMap(Mesh[], String[]) - Static method in class com.jme3.bullet.animation.RagUtils
-
Assign each mesh vertex to a bone/torso link and add its location (mesh coordinates in bind pose) to that link's list.
- copyAabb(BoundingBox) - Method in class com.jme3.bullet.collision.shapes.infos.BoundingValueHierarchy
-
Copy the bounds of the hierarchy.
- copyAll(CharacterController) - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Copy all parameter values from the specified controller.
- copyAll(SoftBodyConfig) - Method in class com.jme3.bullet.objects.infos.SoftBodyConfig
-
Copy all parameter values from the specified config.
- copyAll(SoftBodyWorldInfo) - Method in class com.jme3.bullet.SoftBodyWorldInfo
-
Copy all parameter values from the specified info.
- copyAll(SolverInfo) - Method in class com.jme3.bullet.SolverInfo
-
Copy all parameter values from the specified info.
- copyAxis(Vector3f) - Method in class com.jme3.bullet.joints.SoftAngularJoint
-
Copy the joint axis.
- copyCenter(int, Vector3f) - Method in class com.jme3.bullet.collision.shapes.MultiSphere
-
Copy the location of the center of the indexed sphere.
- copyClusterCenters(FloatBuffer) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Copy the center-of-mass locations of all clusters in this body.
- copyClusterMasses(FloatBuffer) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Copy the masses of all clusters in this body.
- copyClusterVelocities(FloatBuffer) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Copy the (linear) velocities of all clusters in this body.
- copyConstraintProperties(Constraint) - Method in class com.jme3.bullet.joints.Constraint
-
Copy common properties from another constraint.
- copyFaces(IntBuffer) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Copy the node indices of all faces in this body.
- copyGravity(Vector3f) - Method in class com.jme3.bullet.SoftBodyWorldInfo
-
Copy the gravitational acceleration.
- copyHullVertices() - Method in class com.jme3.bullet.collision.shapes.HullCollisionShape
-
Copy the unscaled vertex locations of the optimized convex hull.
- copyIndices() - Method in class com.jme3.bullet.collision.shapes.infos.IndexedMesh
-
Copy the triangle indices.
- copyLinks(IntBuffer) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Copy the node indices of all links in this body.
- copyLocation(Vector3f) - Method in class com.jme3.bullet.joints.SoftLinearJoint
-
Copy the joint location.
- copyLocations(FloatBuffer) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Copy the locations of all nodes in this body.
- copyMasses(FloatBuffer) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Copy the masses of all nodes in this body.
- copyNormals(FloatBuffer) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Copy the normal vectors of all nodes in this body.
- copyOffset(Vector3f) - Method in class com.jme3.bullet.collision.shapes.infos.ChildCollisionShape
-
Copy the translation in the parent's coordinate system.
- copyPcoProperties(PhysicsCollisionObject) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Copy common properties from another collision object.
- copyPivot(Vector3f) - Method in class com.jme3.bullet.joints.Anchor
-
Copy the location of the connection point in the rigid body at the B end.
- copyQuantization(Vector3f) - Method in class com.jme3.bullet.collision.shapes.infos.BoundingValueHierarchy
-
Copy the quantization vector of the hierarchy.
- copyRotation(Quaternion) - Method in class com.jme3.bullet.collision.shapes.infos.ChildCollisionShape
-
Copy the rotation in the parent's coordinate system.
- copyRotationMatrix(Matrix3f) - Method in class com.jme3.bullet.collision.shapes.infos.ChildCollisionShape
-
Copy the rotation in the parent's coordinate system.
- copyShapeProperties(CollisionShape) - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Copy common properties from another
CollisionShape
. - copyTetras(IntBuffer) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Copy the node indices of all tetrahedra in this body.
- copyTransform(Transform) - Method in class com.jme3.bullet.collision.shapes.infos.ChildCollisionShape
-
Copy the Transform relative to the parent's coordinate system.
- copyTriangle(int, Triangle) - Method in class com.jme3.bullet.collision.shapes.infos.IndexedMesh
-
Copy the vertex positions of the specified triangle.
- copyTriangles() - Method in class com.jme3.bullet.collision.shapes.infos.IndexedMesh
-
Copy the unindexed triangle vertices to a new buffer.
- copyVelocities(FloatBuffer) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Copy the (linear) velocities of all nodes in this body.
- copyVertex(int, Vector3f) - Method in class com.jme3.bullet.collision.shapes.SimplexCollisionShape
-
Copy the indexed vertex.
- copyVertexPositions() - Method in class com.jme3.bullet.collision.shapes.infos.IndexedMesh
-
Copy the vertex positions to a new buffer.
- copyVertices() - Method in class com.jme3.bullet.collision.shapes.SimplexCollisionShape
-
Copy the unscaled vertex locations.
- copyWaterNormal(Vector3f) - Method in class com.jme3.bullet.SoftBodyWorldInfo
-
Copy the normal direction of the water surface.
- correctAxes(Transform) - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Apply the inverse of the specified Transform to each child shape.
- countAttachments() - Method in class com.jme3.bullet.animation.DacConfiguration
-
Count the attachments.
- countCachedMeshes() - Static method in class com.jme3.bullet.util.DebugShapeFactory
-
Count how many debug meshes are cached.
- countChildren() - Method in class com.jme3.bullet.animation.PhysicsLink
-
Count this link's immediate children in the link hierarchy.
- countChildren() - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Count the child shapes.
- countClampedCcdMotions() - Static method in class com.jme3.bullet.util.NativeLibrary
-
Count the cumulative number of clamped CCD motions (native variable: gNumClampedCcdMotions).
- countClusters() - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Count the clusters in this body.
- countCollisionGroupListeners() - Method in class com.jme3.bullet.CollisionSpace
-
Count how many collision-group listeners are registered with the space.
- countCollisionListeners() - Method in interface com.jme3.bullet.ContactManager
-
Count how many collision listeners are registered.
- countCollisionListeners() - Method in class com.jme3.bullet.DefaultContactManager
-
Count how many collision listeners are registered.
- countCollisionListeners() - Method in class com.jme3.bullet.PhysicsSpace
-
Count how many collision listeners are registered with the space.
- countCollisionObjects() - Method in class com.jme3.bullet.CollisionSpace
-
Count the collision objects in the space.
- countColumns() - Method in class com.jme3.bullet.collision.shapes.HeightfieldCollisionShape
-
Count how many columns are in the heightfield.
- countConfiguredLinks() - Method in class com.jme3.bullet.MultiBody
-
Count the configured links in this MultiBody.
- countDofs() - Method in class com.jme3.bullet.MultiBody
-
Count the degrees of freedom.
- countDofs() - Method in class com.jme3.bullet.MultiBodyLink
-
Count the degrees of freedom in the joint.
- countEnds() - Method in class com.jme3.bullet.joints.PhysicsJoint
-
Count how many ends this joint has.
- countExceptions() - Method in class jme3utilities.minie.FilterAll
-
Count how many exceptions there are.
- countFaces() - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Count the faces in this body.
- countGroups(CollisionSpace, int[]) - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Enumerate disconnected groups of connected children.
- countHullVertices() - Method in class com.jme3.bullet.collision.shapes.HullCollisionShape
-
Count the number of vertices in the optimized convex hull.
- countIgnored() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Count the collision objects in this object's ignore list.
- countJoints() - Method in class com.jme3.bullet.DeformableSpace
-
Count the joints in this space, including anchors and soft-body joints.
- countJoints() - Method in class com.jme3.bullet.objects.PhysicsBody
-
Count how many joints connect to this body.
- countJoints() - Method in class com.jme3.bullet.PhysicsSoftSpace
-
Count the joints in this space, including anchors and soft-body joints.
- countJoints() - Method in class com.jme3.bullet.PhysicsSpace
-
Count the joints in the space.
- countLeafNodes() - Method in class com.jme3.bullet.collision.shapes.infos.BoundingValueHierarchy
-
Count the leaf nodes in the hierarchy.
- countLinkedBones() - Method in class com.jme3.bullet.animation.DacConfiguration
-
Count the linked bones.
- countLinks() - Method in class com.jme3.bullet.animation.DacConfiguration
-
Count the links.
- countLinks() - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Count the links in this body.
- countManaged() - Method in class com.jme3.bullet.animation.BoneLink
-
Determine the number of managed skeleton bones or armature joints.
- countManaged() - Method in class com.jme3.bullet.animation.TorsoLink
-
Determine the number of managed skeleton bones or armature joints.
- countManifolds() - Method in class com.jme3.bullet.PhysicsSpace
-
Count the collision manifolds in the space.
- countMeshTriangles() - Method in class com.jme3.bullet.collision.shapes.GImpactCollisionShape
-
Count how many triangles are in the mesh.
- countMeshTriangles() - Method in class com.jme3.bullet.collision.shapes.MeshCollisionShape
-
Count how many triangles are in the mesh.
- countMeshVertices() - Method in class com.jme3.bullet.collision.shapes.GImpactCollisionShape
-
Count how many vertices are in the mesh.
- countMeshVertices() - Method in class com.jme3.bullet.collision.shapes.HeightfieldCollisionShape
-
Count how many heights are in the heightfield.
- countMeshVertices() - Method in class com.jme3.bullet.collision.shapes.HullCollisionShape
-
Count the vertices used to generate the hull.
- countMeshVertices() - Method in class com.jme3.bullet.collision.shapes.MeshCollisionShape
-
Count how many vertices are in the mesh.
- countMeshVertices() - Method in class com.jme3.bullet.collision.shapes.SimplexCollisionShape
-
Count the points used to generate the simplex.
- countMultiBodies() - Method in class com.jme3.bullet.MultiBodySpace
-
Count the multibodies in this space.
- countNodes() - Method in class com.jme3.bullet.collision.shapes.infos.BoundingValueHierarchy
-
Count all nodes in the hierarchy.
- countNodes() - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Count the nodes in this body.
- countNodesInCluster(int) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Count the nodes in the indexed cluster.
- countPinnedNodes() - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Count the pinned nodes in this body.
- countPoints(long) - Static method in class com.jme3.bullet.collision.PersistentManifolds
-
Return the number of points in the specified manifold (native field: m_cachedPoints).
- countPositionVariables() - Method in class com.jme3.bullet.MultiBody
-
Count the position variables in this MultiBody.
- countPositionVariables() - Method in class com.jme3.bullet.MultiBodyLink
-
Count the position variables in the joint.
- countRigidBodies() - Method in class com.jme3.bullet.PhysicsSpace
-
Count the rigid bodies in the space, including vehicles.
- countRows() - Method in class com.jme3.bullet.collision.shapes.HeightfieldCollisionShape
-
Count how many rows are in the heightfield.
- countSoftBodies() - Method in class com.jme3.bullet.DeformableSpace
-
Count the soft bodies in this space.
- countSoftBodies() - Method in class com.jme3.bullet.PhysicsSoftSpace
-
Count the soft bodies in this space.
- countSolvers() - Method in class com.jme3.bullet.BulletAppState
-
Count the solvers in the thread-safe pool.
- countSolvers() - Method in class com.jme3.bullet.CollisionSpace
-
Count the worker threads.
- countSpheres() - Method in class com.jme3.bullet.collision.shapes.MultiSphere
-
Count the spheres in the shape.
- countSubmeshes() - Method in class com.jme3.bullet.collision.shapes.GImpactCollisionShape
-
Count how many submeshes are in the mesh.
- countSubmeshes() - Method in class com.jme3.bullet.collision.shapes.infos.CompoundMesh
-
Count how many submeshes are in this mesh.
- countSubmeshes() - Method in class com.jme3.bullet.collision.shapes.MeshCollisionShape
-
Count how many submeshes are in the mesh.
- countSubtreeHeaders() - Method in class com.jme3.bullet.collision.shapes.infos.BoundingValueHierarchy
-
Count the subtree headers in the hierarchy (native field: m_SubtreeHeaders).
- countTetras() - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Count the tetrahedra in this body.
- countThreads() - Static method in class com.jme3.bullet.util.NativeLibrary
-
Count how many threads are available for task scheduling.
- countTickListeners() - Method in class com.jme3.bullet.PhysicsSpace
-
Count how many tick listeners are registered with the space.
- countTrackers() - Static method in class com.jme3.bullet.NativePhysicsObject
-
Count how many native objects are being tracked.
- countTriangles() - Method in class com.jme3.bullet.collision.shapes.infos.CompoundMesh
-
Count how many triangles are in this mesh.
- countTriangles() - Method in class com.jme3.bullet.collision.shapes.infos.IndexedMesh
-
Count how many triangles are in this mesh.
- countVertices() - Method in class com.jme3.bullet.collision.shapes.infos.CompoundMesh
-
Count how many vertices are in this mesh.
- countVertices() - Method in class com.jme3.bullet.collision.shapes.infos.IndexedMesh
-
Count how many vertices are in this mesh.
- countWheels() - Method in class com.jme3.bullet.objects.infos.VehicleController
-
Determine the number of wheels in this controller.
- crash() - Static method in class com.jme3.bullet.util.NativeLibrary
-
Crash the JVM with an EXCEPTION_ACCESS_VIOLATION or SIGILL.
- create() - Method in class com.jme3.bullet.CollisionSpace
-
Must be invoked on the designated physics thread.
- create() - Method in class com.jme3.bullet.DeformableSpace
-
Must be invoked on the designated physics thread.
- create() - Method in class com.jme3.bullet.MultiBodySpace
-
Must be invoked on the designated physics thread.
- create() - Method in class com.jme3.bullet.PhysicsSoftSpace
-
Must be invoked on the designated physics thread.
- create() - Method in class com.jme3.bullet.PhysicsSpace
-
Must be invoked on the designated physics thread.
- createBoxShape(Spatial) - Static method in class com.jme3.bullet.util.CollisionShapeFactory
-
Create a simplified shape for a movable object, based on the axis-aligned bounding boxes of its meshes.
- createCollisionShape() - Method in class com.jme3.bullet.control.RigidBodyControl
-
Set the body's CollisionShape based on the controlled spatial and its descendants.
- createDebugAppState() - Method in class com.jme3.bullet.BulletAppState
-
Create the configured debug-visualization app state.
- createDebugAppState() - Method in class com.jme3.bullet.MultiBodyAppState
-
Create the configured debug-visualization app state.
- createDebugAppState() - Method in class com.jme3.bullet.SoftPhysicsAppState
-
Create the configured debug-visualization app state.
- createDynamicMeshShape(Spatial) - Static method in class com.jme3.bullet.util.CollisionShapeFactory
-
Create a shape for a movable object, based on the convex hulls of its model's meshes.
- createGImpactShape(Spatial) - Static method in class com.jme3.bullet.util.CollisionShapeFactory
-
Create a mesh-accurate shape for a movable object, based on its model.
- createJoint(long, long, Vector3f, Matrix3f, Vector3f, Matrix3f, boolean) - Method in class com.jme3.bullet.joints.SixDofJoint
-
Create a double-ended
btGeneric6DofConstraint
. - createJoint(long, long, Vector3f, Matrix3f, Vector3f, Matrix3f, boolean) - Method in class com.jme3.bullet.joints.SixDofSpringJoint
-
Create a double-ended
btGeneric6DofSpringConstraint
. - createJoint1(long, Vector3f, Matrix3f, boolean) - Method in class com.jme3.bullet.joints.SixDofJoint
-
Create a single-ended
btGeneric6DofConstraint
. - createJoint1(long, Vector3f, Matrix3f, boolean) - Method in class com.jme3.bullet.joints.SixDofSpringJoint
-
Create a single-ended
btGeneric6DofSpringConstraint
. - createMergedBoxShape(Spatial) - Static method in class com.jme3.bullet.util.CollisionShapeFactory
-
Create a very simple shape for an object, based its model's bounding box.
- createMergedHullShape(Spatial) - Static method in class com.jme3.bullet.util.CollisionShapeFactory
-
Create a simplified shape for a movable object, based the convex hull of its model.
- createMergedMeshShape(Spatial) - Static method in class com.jme3.bullet.util.CollisionShapeFactory
-
Create a mesh-accurate shape for an immovable object, based on its model.
- createMeshShape(Spatial) - Static method in class com.jme3.bullet.util.CollisionShapeFactory
-
Create a mesh-accurate shape for an immovable object, based on its model.
- createPhysicsSpace(Vector3f, Vector3f, PhysicsSpace.BroadphaseType) - Method in class com.jme3.bullet.BulletAppState
-
Create the configured
PhysicsSpace
. - createPhysicsSpace(Vector3f, Vector3f, PhysicsSpace.BroadphaseType) - Method in class com.jme3.bullet.MultiBodyAppState
-
Create the configured MultiBodySpace.
- createPhysicsSpace(Vector3f, Vector3f, PhysicsSpace.BroadphaseType) - Method in class com.jme3.bullet.SoftPhysicsAppState
-
Create the configured PhysicsSpace.
- createSpatialData(Spatial) - Method in class com.jme3.bullet.animation.DacLinks
-
Create spatial-dependent data.
- createSpatialData(Spatial) - Method in class com.jme3.bullet.control.AbstractPhysicsControl
-
Create spatial-dependent data.
- createSpatialData(Spatial) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Create spatial-dependent data.
- createSpatialData(Spatial) - Method in class com.jme3.bullet.control.CharacterControl
-
Create spatial-dependent data.
- createSpatialData(Spatial) - Method in class com.jme3.bullet.control.JoinedBodyControl
-
Create spatial-dependent data.
- createSpatialData(Spatial) - Method in class com.jme3.bullet.control.SoftBodyControl
-
Create spatial-dependent data.
- createTestPoint() - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Create a manifold point (for testing) that will never be freed.
- createVehicle(PhysicsSpace) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Used internally, creates the controller when the vehicle is added to a PhysicsSpace.
- createVhacdShape(Spatial, VHACDParameters, CompoundCollisionShape) - Static method in class com.jme3.bullet.util.CollisionShapeFactory
-
Create a shape for a dynamic object using classic V-HACD.
- createVhacdShape(Spatial, Vhacd4Parameters, CompoundCollisionShape) - Static method in class com.jme3.bullet.util.CollisionShapeFactory
-
Create a shape for a dynamic object using V-HACD version 4.
- createWireMaterial(AssetManager, ColorRGBA, String, int) - Method in class com.jme3.bullet.debug.BulletDebugAppState
-
Create the specified wireframe material.
- CullHints - Enum constant in enum class jme3utilities.minie.DumpFlags
-
cull hints in spatials
- CUSTOM_MATERIAL_CALLBACK - Static variable in class com.jme3.bullet.collision.CollisionFlag
-
flag to enable a custom material callback for per-triangle friction/restitution (not supported by Minie)
- CustomConvexShape - Class in com.jme3.bullet.collision.shapes
-
An abstract base class for collision shapes defined in terms of their supporting vertices, based on Bullet's
btConvexInternalShape
. - CustomConvexShape() - Constructor for class com.jme3.bullet.collision.shapes.CustomConvexShape
-
No-argument constructor needed by SavableClassUtil.
- CustomConvexShape(float, float, float) - Constructor for class com.jme3.bullet.collision.shapes.CustomConvexShape
-
Instantiate a custom collision shape with the specified extents.
- CustomConvexShape(Vector3f) - Constructor for class com.jme3.bullet.collision.shapes.CustomConvexShape
-
Instantiate a custom collision shape with the specified extents.
- customizeMesh(Mesh) - Method in interface com.jme3.bullet.debug.MeshCustomizer
-
Customize the specified Mesh.
- cutLink(int, int, float) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Cut a pre-existing link in this body.
- Cylinder - Enum constant in enum class com.jme3.bullet.animation.ShapeHeuristic
-
rotated cylinder
- CylinderCollisionShape - Class in com.jme3.bullet.collision.shapes
-
A cylindrical collision shape based on Bullet's
btCylinderShapeX
,btCylinderShape
, orbtCylinderShapeZ
. - CylinderCollisionShape() - Constructor for class com.jme3.bullet.collision.shapes.CylinderCollisionShape
-
No-argument constructor needed by SavableClassUtil.
- CylinderCollisionShape(float, float, int) - Constructor for class com.jme3.bullet.collision.shapes.CylinderCollisionShape
-
Instantiate a cylinder shape around the specified main (height) axis.
- CylinderCollisionShape(Vector3f) - Constructor for class com.jme3.bullet.collision.shapes.CylinderCollisionShape
-
Instantiate a Z-axis cylinder shape with the specified half extents.
- CylinderCollisionShape(Vector3f, int) - Constructor for class com.jme3.bullet.collision.shapes.CylinderCollisionShape
-
Instantiate a cylinder shape around the specified main (height) axis.
- CylinderCollisionShape(FloatBuffer, int, int, int) - Constructor for class com.jme3.bullet.collision.shapes.CylinderCollisionShape
-
Instantiate a cylinder shape that encloses the sample locations in the specified FloatBuffer range.
D
- DacConfiguration - Class in com.jme3.bullet.animation
-
Configure a DynamicAnimControl and access its configuration.
- DacConfiguration() - Constructor for class com.jme3.bullet.animation.DacConfiguration
-
Instantiate an enabled Control without any attachments or linked bones (torso only).
- DacLinks - Class in com.jme3.bullet.animation
-
Access a DynamicAnimControl at the PhysicsLink level once it's been added to a Spatial.
- DacLinks() - Constructor for class com.jme3.bullet.animation.DacLinks
-
Instantiate an enabled control without any linked bones or attachments (torso only).
- DacUserFilter - Class in jme3utilities.minie
-
A simple DebugAppStateFilter that selects physics objects associated with a specific DynamicAnimControl.
- DacUserFilter(DacLinks) - Constructor for class jme3utilities.minie.DacUserFilter
-
Instantiate a filter for the specified DynamicAnimControl.
- damping() - Method in class com.jme3.bullet.animation.DacConfiguration
-
Return the damping ratio for new rigid bodies.
- Damping - Enum constant in enum class com.jme3.bullet.joints.motors.MotorParam
-
spring's viscous damping ratio (m_springDamping, default=0)
- Damping - Enum constant in enum class com.jme3.bullet.objects.infos.Sbcp
-
damping coefficient (≥0, ≤1, default=0, native field: kDP)
- Dantzig - Enum constant in enum class com.jme3.bullet.SolverType
-
btDantzigSolver: Mixed Linear Complementarity Problem (MLCP) direct solver using the Dantzig Algorithm
- DBVT - Enum constant in enum class com.jme3.bullet.PhysicsSpace.BroadphaseType
-
btDbvtBroadphase: a fast, dynamic bounding-volume hierarchy based on AABB tree to allow quicker addition/removal of physics objects
- DEBUG_BLUE - Variable in class com.jme3.bullet.debug.DebugTools
-
unshaded blue material
- DEBUG_GREEN - Variable in class com.jme3.bullet.debug.DebugTools
-
unshaded green material
- DEBUG_MAGENTA - Variable in class com.jme3.bullet.debug.DebugTools
-
unshaded magenta material
- DEBUG_PINK - Variable in class com.jme3.bullet.debug.DebugTools
-
unshaded pink material
- DEBUG_RED - Variable in class com.jme3.bullet.debug.DebugTools
-
unshaded red material
- DEBUG_YELLOW - Variable in class com.jme3.bullet.debug.DebugTools
-
unshaded yellow material
- debugAppState - Variable in class com.jme3.bullet.debug.AbstractPhysicsDebugControl
-
AppState that this Control serves
- debugAxisLength() - Method in class com.jme3.bullet.BulletAppState
-
Determine the length of the debug axis arrows.
- debugAxisLineWidth() - Method in class com.jme3.bullet.BulletAppState
-
Determine the line width of the debug axis arrows.
- DebugConfiguration - Class in com.jme3.bullet.debug
-
Configuration data for physics (debug) visualization.
- DebugConfiguration() - Constructor for class com.jme3.bullet.debug.DebugConfiguration
-
Instantiate a configuration with no space and no viewports.
- DebugInitListener - Interface in com.jme3.bullet.debug
-
Callback interface used to add lighting to the debug scene.
- debugMeshInit(Mesh) - Method in interface com.jme3.bullet.debug.DebugMeshInitListener
-
Callback from DebugShapeFactory or SoftBodyDebugControl, invoked just after the mesh positions and normals are initialized.
- debugMeshInit(Mesh) - Method in class com.jme3.bullet.util.PlaneDmiListener
-
Callback from DebugShapeFactory, invoked just after the mesh positions and normals are initialized.
- debugMeshInitListener() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Access the listener for new debug meshes.
- DebugMeshInitListener - Interface in com.jme3.bullet.debug
-
Callback interface used to add texture coordinates to a debug mesh.
- debugMeshNormals() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Determine which normals to include in new debug meshes.
- debugMeshResolution() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Return the resolution for new debug meshes.
- debugNode - Variable in class com.jme3.bullet.debug.DebugTools
-
node for attaching debug geometries
- debugNumSides() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Determine how many sides of this object's default debug materials are visible.
- DebugShapeFactory - Class in com.jme3.bullet.util
-
A utility class to generate debug meshes for Bullet collision shapes.
- debugSpatial - Variable in class com.jme3.bullet.debug.BulletCharacterDebugControl
-
Spatial to visualize lastShape (not null)
- DebugTools - Class in com.jme3.bullet.debug
-
Debugging aids.
- DebugTools(AssetManager) - Constructor for class com.jme3.bullet.debug.DebugTools
-
Instantiate a set of debug tools.
- debugVertices(CollisionShape, int) - Static method in class com.jme3.bullet.util.DebugShapeFactory
-
Determine vertex locations for the specified collision shape.
- DefaultContactManager - Class in com.jme3.bullet
-
The default implementation of the ContactManager interface.
- DefaultContactManager(PhysicsSpace) - Constructor for class com.jme3.bullet.DefaultContactManager
-
Instantiate a manager for the specified PhysicsSpace.
- defaultForRotationMotor() - Method in enum class com.jme3.bullet.joints.motors.MotorParam
-
Determine the default value for this parameter in a RotationMotor.
- defaultForTranslationMotor() - Method in enum class com.jme3.bullet.joints.motors.MotorParam
-
Determine the default value for this parameter in a TranslationMotor.
- defaultReturnValue() - Method in class jme3utilities.minie.FilterAll
-
Return the value returned by displayObject() for non-exceptional arguments.
- DeformableSpace - Class in com.jme3.bullet
-
A MultiBodySpace that supports deformables, with its own
btDeformableMultiBodyDynamicsWorld
. - DeformableSpace(Vector3f, Vector3f, PhysicsSpace.BroadphaseType, SolverType) - Constructor for class com.jme3.bullet.DeformableSpace
-
Instantiate a DeformableSpace with the specified contact-and-constraint solver.
- defValue() - Method in enum class com.jme3.bullet.objects.infos.Cluster
-
Determine the default value for this parameter.
- defValue() - Method in enum class com.jme3.bullet.objects.infos.Sbcp
-
Determine the default value for this parameter.
- density() - Method in class com.jme3.bullet.animation.PhysicsLink
-
Read the average density of the rigid body.
- Density - Enum constant in enum class com.jme3.bullet.animation.MassHeuristic
-
multiply the configured parameter by the unscaled volume of the CollisionShape
- describe(int) - Static method in class com.jme3.bullet.objects.infos.ConfigFlag
-
Generate a textual description of the specified flags.
- describe(int) - Static method in class com.jme3.bullet.RayTestFlag
-
Generate a textual description of the specified flags.
- describe(int) - Static method in class com.jme3.bullet.SolverMode
-
Generate a textual description of the specified flags.
- describe(CollisionShape) - Method in class jme3utilities.minie.PhysicsDescriber
-
Generate a textual description for a CollisionShape.
- describe(CollisionConfiguration) - Method in class jme3utilities.minie.PhysicsDescriber
-
Generate a textual description for a CollisionConfiguration.
- describe(RotationalLimitMotor) - Method in class jme3utilities.minie.PhysicsDescriber
-
Describe the specified RotationalLimitMotor.
- describe(TranslationalLimitMotor, int) - Method in class jme3utilities.minie.PhysicsDescriber
-
Describe the indexed axis of the specified TranslationalLimitMotor.
- describe(PhysicsJoint) - Method in class jme3utilities.minie.PhysicsDescriber
-
Generate a brief textual description for a PhysicsJoint.
- describe(SoftBodyMaterial) - Method in class jme3utilities.minie.PhysicsDescriber
-
Generate a brief textual description for the specified PhysicsSoftBody.Material
- describe(PhysicsRigidBody) - Static method in class jme3utilities.minie.MyPco
-
Briefly describe a rigid body for MyControlP or PhysicsDumper.
- describe(VehicleWheel) - Method in class jme3utilities.minie.PhysicsDescriber
-
Describe the specified VehicleWheel.
- describe(SoftBodyWorldInfo) - Method in class jme3utilities.minie.PhysicsDescriber
-
Generate a brief textual description for the specified SoftBodyWorldInfo.
- describe(Control) - Static method in class jme3utilities.minie.MyControlP
-
Generate a textual description of a scene-graph control.
- describe(Control) - Method in class jme3utilities.minie.PhysicsDescriber
-
Generate a textual description of a scene-graph control.
- describe1(SoftBodyConfig) - Method in class jme3utilities.minie.PhysicsDescriber
-
Generate the first line of a textual description for the specified SoftBodyConfig.
- describe2(SoftBodyConfig) - Method in class jme3utilities.minie.PhysicsDescriber
-
Generate the 2nd line of a brief textual description for the specified SoftBodyConfig.
- describe2(VehicleWheel) - Method in class jme3utilities.minie.PhysicsDescriber
-
Generate the 2nd line of a textual description for the specified VehicleWheel.
- describeAngular(SixDofJoint) - Method in class jme3utilities.minie.PhysicsDescriber
-
Describe the angular components of the specified SixDofJoint.
- describeApplicationData(PhysicsCollisionObject) - Method in class jme3utilities.minie.PhysicsDescriber
-
Describe the application data of a collision object.
- describeDof(New6Dof, int) - Method in class jme3utilities.minie.PhysicsDescriber
-
Describe the indexed degree of freedom of the specified New6Dof constraint.
- describeGroups(PhysicsCollisionObject) - Method in class jme3utilities.minie.PhysicsDescriber
-
Briefly describe the collision group and collide-with groups of the specified collision object.
- describeJointInBody(PhysicsJoint, PhysicsBody, boolean) - Method in class jme3utilities.minie.PhysicsDescriber
-
Describe the specified PhysicsJoint in the context of the specified body.
- describeJointInSpace(PhysicsJoint, boolean) - Method in class jme3utilities.minie.PhysicsDescriber
-
Describe the specified joint in the context of a PhysicsSpace.
- describeLinear(SixDofJoint) - Method in class jme3utilities.minie.PhysicsDescriber
-
Describe the linear components of the specified SixDofJoint.
- describeType(CollisionShape) - Static method in class jme3utilities.minie.MyShape
-
Describe the type of the specified shape.
- describeUser(PhysicsCollisionObject) - Method in class jme3utilities.minie.PhysicsDescriber
-
Describe the user of a collision object.
- destroy() - Method in class com.jme3.bullet.CollisionSpace
-
Remove all collision objects and physics joints.
- destroy() - Method in class com.jme3.bullet.DeformableSpace
-
Remove all collision objects and physics joints.
- destroy() - Method in class com.jme3.bullet.joints.PhysicsJoint
-
Remove this joint from the joint lists of both ends.
- destroy() - Method in class com.jme3.bullet.MultiBodySpace
-
Remove all multibodies, collision objects, and physics joints.
- destroy() - Method in class com.jme3.bullet.PhysicsSoftSpace
-
Remove all collision objects and physics joints.
- destroy() - Method in class com.jme3.bullet.PhysicsSpace
-
Remove all collision objects and physics joints.
- destroySoftBody() - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Destroy the pre-existing btSoftBody (if any) except for its worldInfo.
- detach(String) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Unlink the AttachmentLink associated with the named bone.
- DISABLE_SPU_COLLISION_PROCESSING - Static variable in class com.jme3.bullet.collision.CollisionFlag
-
flag to disable parallel/SPU processing (not supported by Minie)
- DISABLE_VISUALIZE_OBJECT - Static variable in class com.jme3.bullet.collision.CollisionFlag
-
flag to disable debug visualization (not supported by Minie)
- disableAllIKControllers() - Method in class com.jme3.bullet.animation.PhysicsLink
-
Disable all IK controllers.
- DisableHeightfieldAccelerator - Static variable in class com.jme3.bullet.RayTestFlag
-
disable the heightfield raycast accelerator (native value: kF_DisableHeightfieldAccelerator)
- disablePhysicsControls(Spatial) - Static method in class jme3utilities.minie.MyControlP
-
Disable all physics controls added to the specified subtree of the scene graph.
- displayObject(Object) - Method in interface com.jme3.bullet.debug.BulletDebugAppState.DebugAppStateFilter
-
Test whether the specified physics object should be rendered in the debug scene.
- displayObject(Object) - Method in class jme3utilities.minie.AppDataFilter
-
Test whether the specified physics object should be displayed/dumped.
- displayObject(Object) - Method in class jme3utilities.minie.CcdFilter
-
Test whether the specified physics object should be displayed/dumped.
- displayObject(Object) - Method in class jme3utilities.minie.ClassFilter
-
Test whether the specified physics object should be displayed/dumped.
- displayObject(Object) - Method in class jme3utilities.minie.DacUserFilter
-
Test whether the specified physics object should be displayed/dumped.
- displayObject(Object) - Method in class jme3utilities.minie.FilterAll
-
Test whether the specified physics object should be displayed/dumped.
- displayObject(Object) - Method in class jme3utilities.minie.NegativeAppDataFilter
-
Test whether the specified physics object should be displayed/dumped.
- displayObject(Object) - Method in class jme3utilities.minie.UserFilter
-
Test whether the specified physics object should be displayed/dumped.
- distinctVertices() - Method in class com.jme3.bullet.collision.shapes.infos.IndexedMesh
-
Return the set of distinct vertices.
- distributeEvents() - Method in interface com.jme3.bullet.ContactManager
-
Distribute queued collision events to registered listeners.
- distributeEvents() - Method in class com.jme3.bullet.DefaultContactManager
-
Distribute queued collision events to registered listeners.
- distributeEvents() - Method in class com.jme3.bullet.PhysicsSpace
-
Distribute queued collision events to registered listeners.
- Drag - Enum constant in enum class com.jme3.bullet.objects.infos.Sbcp
-
drag coefficient (≥0, default=0, native field: kDG)
- driftIterations() - Method in class com.jme3.bullet.objects.infos.SoftBodyConfig
-
Return the number of drift-solver iterations (native field: diterations).
- dropAttachments() - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Release (to gravity) all unreleased attachments.
- dump(AppState, String) - Method in class jme3utilities.minie.PhysicsDumper
-
Dump the specified AppState.
- dump(BulletAppState) - Method in class jme3utilities.minie.PhysicsDumper
-
Dump the specified BulletAppState.
- dump(CollisionShape, String) - Method in class jme3utilities.minie.PhysicsDumper
-
Dump the specified CollisionShape.
- dump(PhysicsJoint, String) - Method in class jme3utilities.minie.PhysicsDumper
-
Dump the specified PhysicsJoint in a PhysicsSpace context.
- dump(MultiBodyCollider, String) - Method in class jme3utilities.minie.PhysicsDumper
-
Dump the specified MultiBodyCollider.
- dump(PhysicsCharacter, String) - Method in class jme3utilities.minie.PhysicsDumper
-
Dump the specified PhysicsCharacter.
- dump(PhysicsGhostObject, String) - Method in class jme3utilities.minie.PhysicsDumper
-
Dump the specified PhysicsGhostObject.
- dump(PhysicsRigidBody, String) - Method in class jme3utilities.minie.PhysicsDumper
-
Dump the specified PhysicsRigidBody.
- dump(PhysicsSoftBody, String) - Method in class jme3utilities.minie.PhysicsDumper
-
Dump the specified PhysicsSoftBody.
- dump(PhysicsSpace) - Method in class jme3utilities.minie.PhysicsDumper
-
Dump the specified PhysicsSpace.
- dump(PhysicsSpace, String, BulletDebugAppState.DebugAppStateFilter) - Method in class jme3utilities.minie.PhysicsDumper
-
Dump the specified PhysicsSpace with the specified filter.
- dumpBas(BulletAppState, String) - Method in class jme3utilities.minie.PhysicsDumper
-
Dump the specified BulletAppState.
- DumpFlags - Enum Class in jme3utilities.minie
-
Enumerate the flags used to configure a PhysicsDumper.
- dumpMemoryLeaks() - Static method in class com.jme3.bullet.util.NativeLibrary
-
Dump all native-memory allocation/free events to standard output.
- dumpQuickprof() - Static method in class com.jme3.bullet.util.NativeLibrary
-
Dump all Quickprof data to standard output.
- dumpTrackers() - Static method in class com.jme3.bullet.NativePhysicsObject
-
Dump all native-object trackers to
System.out
. - DynamicAnimControl - Class in com.jme3.bullet.animation
-
Before adding this Control to a Spatial, configure it by invoking
DacConfiguration.link(java.lang.String, float, com.jme3.bullet.animation.RangeOfMotion)
for each bone that should have its own rigid body. - DynamicAnimControl() - Constructor for class com.jme3.bullet.animation.DynamicAnimControl
-
Instantiate an enabled Control without any linked bones or attachments (torso only).
- DynamicFriction - Enum constant in enum class com.jme3.bullet.objects.infos.Sbcp
-
dynamic friction coefficient (≥0, <1, default=0.2, native field: kDF)
- dynamicUpdate() - Method in class com.jme3.bullet.animation.AttachmentLink
-
Update this link in Dynamic mode, setting the local transform of the attached model based on the transform of the linked rigid body.
- dynamicUpdate() - Method in class com.jme3.bullet.animation.BoneLink
-
Update this link in Dynamic mode, setting the linked bone's transform based on the transform of the rigid body.
- dynamicUpdate() - Method in class com.jme3.bullet.animation.PhysicsLink
-
Update this link in Dynamic mode, setting the linked bone's transform based on the transform of the rigid body.
- dynamicUpdate() - Method in class com.jme3.bullet.animation.TorsoLink
-
Update this link in Dynamic mode, setting the local transform of the model's root spatial based on the transform of the linked rigid body.
E
- either - Static variable in class com.jme3.bullet.collision.AfMode
-
bitmask for either kind of anisotropic friction
- EmptyShape - Class in com.jme3.bullet.collision.shapes
-
An empty collision shape based on Bullet's
btEmptyShape
. - EmptyShape() - Constructor for class com.jme3.bullet.collision.shapes.EmptyShape
-
No-argument constructor needed by SavableClassUtil.
- EmptyShape(boolean) - Constructor for class com.jme3.bullet.collision.shapes.EmptyShape
-
Instantiate an empty shape.
- enableChildColoring - Static variable in class com.jme3.bullet.debug.BulletDebugAppState
-
fake Material to indicate child coloring of a CompoundCollisionShape
- enableContactFilter - Variable in class com.jme3.bullet.collision.shapes.CollisionShape
-
copy of the contact-filter enable flag
- enableMotor(boolean, float, float) - Method in class com.jme3.bullet.joints.HingeJoint
-
Enable or disable this joint's motor.
- enablePhysicsControls(Spatial, PhysicsSpace) - Static method in class jme3utilities.minie.MyControlP
-
Enable all physics controls added to the specified subtree of the scene graph and configure their physics spaces.
- enableSpring(int, boolean) - Method in class com.jme3.bullet.joints.New6Dof
-
Enable or disable the spring for the indexed degree of freedom.
- enableSpring(int, boolean) - Method in class com.jme3.bullet.joints.SixDofSpringJoint
-
Enable or disable the spring for the indexed degree of freedom.
- enqueue(Callable<V>) - Method in class com.jme3.bullet.PhysicsSpace
-
Invoke the specified callable during the next simulation step.
- enqueueOnThisThread(Callable<V>) - Static method in class com.jme3.bullet.PhysicsSpace
-
Enqueue a callable on the currently executing thread.
- equals(Object) - Method in class com.jme3.bullet.animation.LinkConfig
-
Test for exact equivalence with another Object.
- equals(Object) - Method in class com.jme3.bullet.NativePhysicsObject
-
Test for ID equality with another object.
- equals(Object) - Method in class vhacd.VHACDParameters
-
Test for exact equivalence with another Object.
- equals(Object) - Method in class vhacd4.Vhacd4Parameters
-
Test for exact equivalence with another Object.
- Equilibrium - Enum constant in enum class com.jme3.bullet.joints.motors.MotorParam
-
spring's equilibrium point (m_equilibriumPoint, default=0)
- error - Static variable in class com.jme3.bullet.collision.Activation
-
a disabled collision object: this usually indicates that an error has occurred (native name: DISABLE_SIMULATION)
- escapeIndex(int) - Method in class com.jme3.bullet.collision.shapes.infos.BoundingValueHierarchy
-
Return the escape index of the specified node.
- eventDispatchImpulseThreshold() - Method in class com.jme3.bullet.animation.DacConfiguration
-
Return the event-dispatch impulse threshold of this control.
- exempt - Static variable in class com.jme3.bullet.collision.Activation
-
a collision object that's exempt from deactivation, such as a vehicle or a kinematic rigid body (native name: DISABLE_DEACTIVATION)
- expectedVersion - Static variable in class com.jme3.bullet.util.NativeLibrary
-
expected version string of the native library
F
- F_OneSided - Enum constant in enum class com.jme3.bullet.objects.infos.Aero
-
Face normals are taken as they are.
- F_TwoSided - Enum constant in enum class com.jme3.bullet.objects.infos.Aero
-
Face normals are flipped to match velocity.
- F_TwoSidedLiftDrag - Enum constant in enum class com.jme3.bullet.objects.infos.Aero
-
Face normals are flipped to match velocity.
- FacesAndLinks - Enum constant in enum class com.jme3.bullet.control.UseTriangles
-
use triangle indices to generate soft-body faces and links
- FacesOnly - Enum constant in enum class com.jme3.bullet.control.UseTriangles
-
use triangle indices to generate soft-body faces only
- fail() - Static method in class com.jme3.bullet.util.NativeLibrary
-
Execute btAssert(0).
- FillMode - Enum Class in com.jme3.bullet
-
Enumerate algorithms to generate a solid object from voxels (native name: FillMode).
- FilterAll - Class in jme3utilities.minie
-
A simple DebugAppStateFilter that returns true for most physics objects (or false for most physics objects) with specified exceptions.
- FilterAll(boolean) - Constructor for class jme3utilities.minie.FilterAll
-
Instantiate a filter with the specified default return value.
- FilterBackfaces - Static variable in class com.jme3.bullet.RayTestFlag
-
filter back faces (native value: kF_FilterBackfaces)
- finalizeNative(long) - Static method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Finalize the identified btCollisionObject.
- finalizeNative(long) - Static method in class com.jme3.bullet.joints.SoftPhysicsJoint
-
Finalize the
btTypedConstraint
. - findArmatureJoint(String) - Method in class com.jme3.bullet.animation.DacLinks
-
Access the named armature joint.
- findAttachmentLink(String) - Method in class com.jme3.bullet.animation.DacLinks
-
Access the AttachmentLink for the named bone.
- findBone(String) - Method in class com.jme3.bullet.animation.DacLinks
-
Access the named Bone.
- findBoneLink(String) - Method in class com.jme3.bullet.animation.DacLinks
-
Access the BoneLink for the named bone.
- findEnabledRbc(Spatial) - Static method in class jme3utilities.minie.MyControlP
-
Access the first enabled RigidBodyControl added to a Spatial.
- findEnd(PhysicsBody) - Method in class com.jme3.bullet.joints.PhysicsJoint
-
Test whether the specified body is an end of this joint.
- findIndex(CollisionShape) - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Find the first child with the specified shape.
- findInstance(long) - Static method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Find the collision object with the specified ID.
- findLink(String) - Method in class com.jme3.bullet.animation.DacLinks
-
Access the named link.
- findMainBone(Skeleton, Mesh[]) - Static method in class com.jme3.bullet.animation.RagUtils
-
Find the main root bone of a Skeleton, based on its total mesh weight.
- findMainJoint(Armature, Mesh[]) - Static method in class com.jme3.bullet.animation.RagUtils
-
Find the main root joint of an Armature, based on its total mesh weight.
- findManager(Joint) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Find the manager of the specified armature joint.
- findManager(Bone) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Find the manager of the specified Bone.
- findManager(Mesh, int, int[], float[], String[]) - Static method in class com.jme3.bullet.animation.RagUtils
-
Determine which physics link should manage the specified mesh vertex.
- findManagerForVertex(String, Vector3f, Vector3f) - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Find the link that manages the specified vertex and optionally calculate the location of that vertex.
- findOtherBody(PhysicsBody) - Method in class com.jme3.bullet.joints.PhysicsJoint
-
Access the remaining body of this joint.
- findSControl(Spatial) - Static method in class com.jme3.bullet.animation.RagUtils
-
Access the SkeletonControl or SkinningControl in the specified subtree, assuming it doesn't contain more than one.
- firstValue - Static variable in class com.jme3.bullet.collision.Activation
-
lowest legal value, for range checks
- Fixed - Enum constant in enum class com.jme3.bullet.MultiBodyJointType
-
fixed joint (native name: eFixed)
- fixToWorld(PhysicsLink, boolean) - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Add an IK joint that will fix the specified link in its current position.
- FloodFill - Enum constant in enum class com.jme3.bullet.FillMode
-
use a flood fill to distinguish inside from outside (native name: FLOOD_FILL)
- fluid - Static variable in class com.jme3.bullet.collision.PcoType
-
unused (native name: CO_HF_FLUID)
- footprint() - Method in class com.jme3.bullet.animation.BoneLink
-
Estimate the footprint of this link.
- footprint(CollisionShape, Transform, int) - Static method in class com.jme3.bullet.util.DebugShapeFactory
-
Estimate the footprint of the specified (non-compound, non-plane) shape.
- footprint(Transform) - Method in class com.jme3.bullet.collision.shapes.infos.IndexedMesh
-
Estimate the footprint of the mesh.
- forwardAxisIndex() - Method in class com.jme3.bullet.objects.infos.VehicleController
-
Determine the index of the vehicle's forward axis.
- forwardAxisIndex() - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Determine the index of this vehicle's forward axis.
- FourSphere - Enum constant in enum class com.jme3.bullet.animation.ShapeHeuristic
-
4-sphere hull to fill the minimal bounding box (good for many bone links)
- freeUnusedObjects() - Static method in class com.jme3.bullet.NativePhysicsObject
-
Free any assigned native objects that are known to be unused.
- freeze(boolean) - Method in class com.jme3.bullet.animation.AttachmentLink
-
Immediately freeze this link.
- freeze(boolean) - Method in class com.jme3.bullet.animation.BoneLink
-
Immediately freeze this link.
- freeze(boolean) - Method in class com.jme3.bullet.animation.PhysicsLink
-
Immediately freeze this link.
- freeze(boolean) - Method in class com.jme3.bullet.animation.TorsoLink
-
Immediately freeze this link.
- freezeSubtree(PhysicsLink, boolean) - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Immediately freeze the specified link and all its descendants.
- FRICTION_ANCHOR - Static variable in class com.jme3.bullet.collision.ContactPointFlag
-
contact has a friction anchor
- fromInputStream(InputStream) - Method in class vhacd.VHACDParameters
-
Read selected parameters from the specified InputStream.
- fromInputStream(InputStream) - Method in class vhacd4.Vhacd4Parameters
-
Read all parameters from the specified InputStream.
- Frozen - Enum constant in enum class com.jme3.bullet.animation.KinematicSubmode
-
frozen in the transform it had when blending started
G
- GearJoint - Class in com.jme3.bullet.joints
-
A joint that couples the angular velocities of two bodies, based on Bullet's btGearConstraint.
- GearJoint() - Constructor for class com.jme3.bullet.joints.GearJoint
-
No-argument constructor needed by SavableClassUtil.
- GearJoint(PhysicsRigidBody, PhysicsRigidBody, Vector3f, Vector3f) - Constructor for class com.jme3.bullet.joints.GearJoint
-
Instantiate a double-ended GearJoint with a 1:1 ratio.
- GearJoint(PhysicsRigidBody, PhysicsRigidBody, Vector3f, Vector3f, float) - Constructor for class com.jme3.bullet.joints.GearJoint
-
Instantiate a double-ended GearJoint with the specified gear ratio.
- generateBendingConstraints(int, SoftBodyMaterial) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Generate bending constraints based on hops in the adjacency graph.
- generateClusters() - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Generate one cluster per tetrahedron (or one per face if there are no tetrahedra).
- generateClusters(int, int) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Generate clusters (K-mean).
- generateIndexMap(FloatBuffer) - Static method in class com.jme3.bullet.util.NativeSoftBodyUtil
-
Create an index map to merge any mesh vertices that share the same position.
- generic - Static variable in class com.jme3.bullet.collision.PcoType
-
default value, unused in Libbulletjme (native name: CO_COLLISION_OBJECT)
- get(MotorParam) - Method in class com.jme3.bullet.joints.motors.RotationMotor
-
Return the value of the specified parameter.
- get(MotorParam, int) - Method in class com.jme3.bullet.joints.New6Dof
-
Return the specified parameter of the indexed degree of freedom.
- get(MotorParam, Vector3f) - Method in class com.jme3.bullet.joints.motors.TranslationMotor
-
Copy the specified parameter of this motor.
- get(Cluster, int) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Read the specified parameter of the indexed cluster.
- get(Sbcp) - Method in class com.jme3.bullet.objects.infos.SoftBodyConfig
-
Return the value of the specified parameter.
- getAccumulatedImpulse() - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Return the accumulated impulse (native field: m_accumulatedImpulse).
- getAccumulatedImpulse(Vector3f) - Method in class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
Copy the accumulated impulse (native field: m_accumulatedImpulse).
- getAccuracy() - Method in class com.jme3.bullet.PhysicsSpace
-
Return the simulation accuracy: the time step used when maxSubSteps>0.
- getACDMode() - Method in class vhacd.VHACDParameters
-
Return the decomposition mode (native field: m_mode).
- getActivationState() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Return this object's activation state (native field: m_activationState1).
- getAlpha() - Method in class vhacd.VHACDParameters
-
Return the bias toward clipping along symmetry planes.
- getAnchor(Vector3f) - Method in class com.jme3.bullet.joints.NewHinge
-
Determine the anchor location for body A.
- getAnchor2(Vector3f) - Method in class com.jme3.bullet.joints.NewHinge
-
Determine the anchor location for body B.
- getAngle() - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Return this motor's current rotation angle (native field: m_currentPosition).
- getAngle1() - Method in class com.jme3.bullet.joints.NewHinge
-
Determine the rotation angle for axis1.
- getAngle2() - Method in class com.jme3.bullet.joints.NewHinge
-
Determine the rotation angle for axis2.
- getAngles(Vector3f) - Method in class com.jme3.bullet.joints.New6Dof
-
Calculate the constraint's rotation angles (native field: m_calculatedAxisAngleDiff).
- getAngles(Vector3f) - Method in class com.jme3.bullet.joints.SixDofJoint
-
Copy the joint's rotation angles.
- getAngularDamping() - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Determine the character's angular damping.
- getAngularDamping() - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Determine this character's angular damping.
- getAngularDamping() - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Return the body's angular damping.
- getAngularFactor() - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
For compatibility with the jme3-jbullet library.
- getAngularFactor(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Copy the body's angular factors.
- getAngularLowerLimit(Vector3f) - Method in class com.jme3.bullet.joints.SixDofJoint
-
Copy the joint's lower limits for rotation on all 3 axes.
- getAngularSleepingThreshold() - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Return the body's angular-motion sleeping threshold.
- getAngularUpperLimit(Vector3f) - Method in class com.jme3.bullet.joints.SixDofJoint
-
Copy the joint's upper limits for rotation on all 3 axes.
- getAngularVelocity() - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
For compatibility with the jme3-jbullet library.
- getAngularVelocity(Vector3f) - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Determine the character's angular velocity.
- getAngularVelocity(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Determine this character's angular velocity.
- getAngularVelocity(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Copy the body's angular velocity.
- getAngularVelocityDp(Vec3d) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Copy the body's angular velocity.
- getAngularVelocityLocal(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Calculate the body's angular velocity in its local coordinates.
- getAnisotropicFriction(Vector3f) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Copy this object's anisotropic friction components (native field: m_anisotropicFriction).
- getApplicationData() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Access any application-specific data associated with the collision object.
- getAppliedImpulse() - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Return the contact point's applied impulse (native field: m_appliedImpulse).
- getAppliedImpulse() - Method in class com.jme3.bullet.joints.Constraint
-
Determine the magnitude of the applied impulse.
- getAppliedImpulse(long) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Return the applied impulse of the specified point (native field: m_appliedImpulse).
- getAppliedImpulseLateral1() - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Return the contact point's applied lateral impulse #1 (native field: m_appliedImpulseLateral1).
- getAppliedImpulseLateral1(long) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Return the applied lateral impulse #1 of the specified point (native field: m_appliedImpulseLateral1).
- getAppliedImpulseLateral2() - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Return the contact point's applied lateral impulse #2 (native field: m_appliedImpulseLateral2).
- getAppliedImpulseLateral2(long) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Return the applied lateral impulse #2 of the specified point (native field: m_appliedImpulseLateral2).
- getArmature() - Method in class com.jme3.bullet.animation.DacLinks
-
Access the Armature.
- getArmatureJoint() - Method in class com.jme3.bullet.animation.PhysicsLink
-
Access the corresponding armature joint.
- getAttachedModel() - Method in class com.jme3.bullet.animation.AttachmentLink
-
Access the attached model (not the attachment node).
- getAttachmentModel(String) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Access the model attached to the named bone.
- getAxis() - Method in class com.jme3.bullet.collision.shapes.CapsuleCollisionShape
-
Return the main (height) axis of the capsule.
- getAxis() - Method in class com.jme3.bullet.collision.shapes.ConeCollisionShape
-
Return the main (height) axis of the cone.
- getAxis() - Method in class com.jme3.bullet.collision.shapes.CylinderCollisionShape
-
Return the main (height) axis of the cylinder.
- getAxis(int, Vector3f) - Method in class com.jme3.bullet.joints.New6Dof
-
Calculate the indexed axis of the Constraint (native field: m_calculatedAxis).
- getAxis1(Vector3f) - Method in class com.jme3.bullet.joints.NewHinge
-
Determine the direction of axis1.
- getAxis2(Vector3f) - Method in class com.jme3.bullet.joints.NewHinge
-
Determine the direction of axis2.
- getAxisA(Vector3f) - Method in class com.jme3.bullet.joints.GearJoint
-
Copy A body's axis of rotation.
- getAxisB(Vector3f) - Method in class com.jme3.bullet.joints.GearJoint
-
Copy the B body's axis of rotation.
- getAxle(Vector3f) - Method in class com.jme3.bullet.objects.VehicleWheel
-
Determine this wheel's axis direction.
- getBaseCollider() - Method in class com.jme3.bullet.MultiBody
-
Access the collider for the base.
- getBaseShape() - Method in class com.jme3.bullet.collision.shapes.Convex2dShape
-
Access the base shape.
- getBeta() - Method in class vhacd.VHACDParameters
-
Return the bias toward clipping along revolution axes (native field: m_beta).
- getBiasFactor() - Method in class com.jme3.bullet.joints.HingeJoint
-
Read this joint's bias factor.
- getBlendListener() - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Access the blend listener.
- getBody() - Method in class com.jme3.bullet.control.SoftBodyControl
-
Access the soft body managed by this Control.
- getBody(JointEnd) - Method in class com.jme3.bullet.joints.PhysicsJoint
-
Access the body at the specified end of this joint.
- getBodyA() - Method in class com.jme3.bullet.joints.Constraint
-
Access the rigid body at the A end.
- getBodyA() - Method in class com.jme3.bullet.joints.PhysicsJoint
-
Access the body at the joint's "A" end.
- getBodyAId(long) - Static method in class com.jme3.bullet.collision.PersistentManifolds
-
Return the native ID of the first collision object (native field: m_body0).
- getBodyB() - Method in class com.jme3.bullet.joints.Constraint
-
Access the rigid body at the B end.
- getBodyB() - Method in class com.jme3.bullet.joints.PhysicsJoint
-
Access the body at the joint's "B" end.
- getBodyBId(long) - Static method in class com.jme3.bullet.collision.PersistentManifolds
-
Return the native ID of the 2nd collision object (native field: m_body1).
- getBone() - Method in class com.jme3.bullet.animation.PhysicsLink
-
Access the corresponding skeleton bone.
- getBoneLinks() - Method in class com.jme3.bullet.animation.DacLinks
-
Access the list of bone links in a pre-order, depth-first traversal of the link hierarchy.
- getBrake() - Method in class com.jme3.bullet.objects.VehicleWheel
-
Determine this wheel's braking impulse (native field: m_brake).
- getBreakingImpulseThreshold() - Method in class com.jme3.bullet.joints.Constraint
-
Determine the breaking impulse threshold.
- getBroadphaseType() - Method in class com.jme3.bullet.BulletAppState
-
Determine which broadphase collision-detection algorithm the PhysicsSpace will use.
- getBroadphaseType() - Method in class com.jme3.bullet.CollisionSpace
-
Return the type of acceleration structure used for broadphase collision detection.
- getBvh() - Method in class com.jme3.bullet.collision.shapes.MeshCollisionShape
-
Access the bounding-value hierarchy.
- getCamera() - Method in class com.jme3.bullet.debug.DebugConfiguration
-
Access the Camera used for visualization.
- getCcdMotionThreshold() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Return the continuous collision detection (CCD) motion threshold (native field: m_ccdMotionThreshold).
- getCcdSquareMotionThreshold() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Return the squared motion threshold.
- getCcdSweptSphereRadius() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Return the radius of the sphere used for continuous collision detection (CCD) (native field: m_ccdSweptSphereRadius).
- getCFM() - Method in class com.jme3.bullet.joints.SoftPhysicsJoint
-
Read the constraint force mixing coefficient (aka CFM).
- getCharacter() - Method in class com.jme3.bullet.control.CharacterControl
-
Access the PhysicsCharacter managed by this Control.
- getCharacterList() - Method in class com.jme3.bullet.PhysicsSpace
-
Enumerate physics characters that have been added to the space and not yet removed.
- getCollider() - Method in class com.jme3.bullet.MultiBodyLink
-
Access the collider for this link.
- getCollideWithGroups() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Return the set of collision groups with which this object can collide.
- getCollisionConfiguration() - Method in class com.jme3.bullet.BulletAppState
-
Return the collision configuration that will be used to instantiate the PhysicsSpace.
- getCollisionGroup() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Return the collision group of this object.
- getCollisionLocation() - Method in class com.jme3.bullet.objects.VehicleWheel
-
For compatibility with the jme3-jbullet library.
- getCollisionLocation(Vector3f) - Method in class com.jme3.bullet.objects.VehicleWheel
-
Determine the location where the wheel touches the ground.
- getCollisionNormal() - Method in class com.jme3.bullet.objects.VehicleWheel
-
For compatibility with the jme3-jbullet library.
- getCollisionNormal(Vector3f) - Method in class com.jme3.bullet.objects.VehicleWheel
-
Determine the normal direction where the wheel touches the ground.
- getCollisionObject() - Method in class com.jme3.bullet.collision.PhysicsRayTestResult
-
Access the collision object that was hit.
- getCollisionObject() - Method in class com.jme3.bullet.collision.PhysicsSweepTestResult
-
Access the collision object that was hit.
- getCollisionShape() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Access the shape of the collision object.
- getCollisionSpace() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Access the space where the collision object is added.
- getCollisionSpace() - Static method in class com.jme3.bullet.CollisionSpace
-
Access the CollisionSpace associated with the current thread.
- getCombinedFriction() - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Return the contact point's combined friction, which is usually the product of the collision-object frictions (native field: m_combinedFriction).
- getCombinedFriction(long) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Return the combined friction of the specified point, which is the product of the collision-object frictions (native field: m_combinedFriction).
- getCombinedRestitution() - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Return the contact point's combined restitution, which is usually the product of the collision-object restitutions (native field: m_combinedRestitution).
- getCombinedRestitution(long) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Return the combined restitution of the specified point, which is the product of the collision-object restitutions (native field: m_combinedRestitution).
- getCombinedRollingFriction() - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Return the contact point's combined rolling friction (native field: m_combinedRollingFriction).
- getCombinedRollingFriction(long) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Return the combined rolling friction of the specified point (native field: m_combinedRollingFriction).
- getCombinedSpinningFriction() - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Return the contact point's combined spinning friction (native field: m_combinedSpinningFriction).
- getCombinedSpinningFriction(long) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Return the combined spinning friction of the specified point (native field: m_combinedSpinningFriction).
- getConfiguration() - Method in class com.jme3.bullet.CollisionSpace
-
Access the tuning parameters.
- getConstraintType(long) - Static method in class com.jme3.bullet.joints.Constraint
-
Read the constraint type.
- getContactDamping() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Return the contact damping (native field: m_contactDamping).
- getContactManager() - Method in class com.jme3.bullet.PhysicsSpace
-
Access the current ContactManager.
- getContactMotion1(long) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Return the contact motion #1 of the specified point (native field: m_contactMotion1).
- getContactMotion2(long) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Return the contact motion #2 of the specified point (native field: m_contactMotion2).
- getContactProcessingThreshold() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Return the contact-processing threshold (native field: m_contactProcessingThreshold).
- getContactStiffness() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Return the contact stiffness (native field: m_contactStiffness).
- getControl() - Method in class com.jme3.bullet.animation.PhysicsLink
-
Access the control that manages this link.
- getController() - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Access this vehicle's controller.
- getControllerId() - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Determine the ID of the btKinematicCharacterController.
- getConvexHullDownSampling() - Method in class vhacd.VHACDParameters
-
Return the precision of the convex-hull generation process (native field: m_convexhullDownsampling).
- getCurrentVehicleSpeedKmHour() - Method in class com.jme3.bullet.objects.infos.VehicleController
-
Determine the vehicle's speed in km/h.
- getCurrentVehicleSpeedKmHour() - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Determine this vehicle's forward velocity as of the previous simulation step.
- getDamping() - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Return this motor's damping (native field: m_damping).
- getDamping() - Method in class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
Return this motor's damping (native field: m_damping).
- getDamping() - Method in class com.jme3.bullet.joints.Point2PointJoint
-
Return the joint's damping ratio.
- getDamping(int) - Method in class com.jme3.bullet.joints.SixDofSpringJoint
-
Return the damping of the indexed degree of freedom.
- getDampingDirAng() - Method in class com.jme3.bullet.joints.SliderJoint
-
Read the joint's damping for on-axis rotation between the limits.
- getDampingDirLin() - Method in class com.jme3.bullet.joints.SliderJoint
-
Read the joint's damping for on-axis translation between the limits.
- getDampingLimAng() - Method in class com.jme3.bullet.joints.SliderJoint
-
Read the joint's damping for on-axis rotation hitting the limits.
- getDampingLimLin() - Method in class com.jme3.bullet.joints.SliderJoint
-
Read the joint's damping for on-axis translation hitting the limits.
- getDampingOrthoAng() - Method in class com.jme3.bullet.joints.SliderJoint
-
Read the joint's damping for off-axis rotation.
- getDampingOrthoLin() - Method in class com.jme3.bullet.joints.SliderJoint
-
Read the joint's damping for off-axis translation.
- getDeactivationDeadline() - Static method in class com.jme3.bullet.objects.PhysicsBody
-
Return the global deactivation deadline.
- getDeactivationTime() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Return the deactivation time (native field: m_deactivationTime).
- getDebugAppState() - Method in class com.jme3.bullet.BulletAppState
-
Access the AppState to manage the debug visualization.
- getDebugCamera() - Method in class com.jme3.bullet.BulletAppState
-
Access the Camera used for debug visualization.
- getDebugConfiguration() - Method in class com.jme3.bullet.BulletAppState
-
Access the configuration for debug visualization.
- getDebugEnabled() - Method in class vhacd.VHACDParameters
-
Test whether debug output is enabled.
- getDebugEnabled() - Method in class vhacd4.Vhacd4Parameters
-
Test whether debug output is enabled.
- getDebugMaterial() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Access the custom debug material, if specified.
- getDebugMesh(CollisionShape) - Static method in class com.jme3.bullet.util.DebugShapeFactory
-
For compatibility with the jme3-jbullet library.
- getDebugShape(PhysicsCollisionObject) - Static method in class com.jme3.bullet.util.DebugShapeFactory
-
Create a Spatial for visualizing the specified collision object.
- getDebugShape(CollisionShape) - Static method in class com.jme3.bullet.util.DebugShapeFactory
-
For compatibility with the jme3-jbullet library.
- getDebugTriangles(CollisionShape, int) - Static method in class com.jme3.bullet.util.DebugShapeFactory
-
Generate vertex locations for triangles to visualize the specified collision shape.
- getDefaultMargin() - Static method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Return the default margin for new shapes that are neither capsules nor spheres.
- getDeformableSpace() - Static method in class com.jme3.bullet.DeformableSpace
-
Access the DeformableSpace running on this thread.
- getDeltaRotation() - Method in class com.jme3.bullet.objects.VehicleWheel
-
Determine how much this wheel has turned since the last simulation step.
- getDescriber() - Method in class jme3utilities.minie.PhysicsDumper
-
Access the Describer used by this Dumper.
- getDirection(Vector3f) - Method in class com.jme3.bullet.objects.VehicleWheel
-
Determine this wheel's suspension direction.
- getDistance1() - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Return the contact point's signed separation distance (native field: m_distance1).
- getDistance1(long) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Return the separation distance of the specified point (native field: m_distance1).
- getDuckedFactor() - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Return the collision-shape height multiplier for ducking.
- getEnableMotor() - Method in class com.jme3.bullet.joints.HingeJoint
-
Test whether this joint's motor is enabled.
- getEngineForce() - Method in class com.jme3.bullet.objects.VehicleWheel
-
Determine this wheel's engine force (native field: m_engineForce).
- getEquilibriumPoint(int) - Method in class com.jme3.bullet.joints.SixDofSpringJoint
-
Return the equilibrium point of the indexed degree of freedom.
- getERP() - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Return this motor's error-reduction parameter at the limits (native field: m_stopERP).
- getERP() - Method in class com.jme3.bullet.joints.SoftPhysicsJoint
-
Read the error-reduction parameter (aka ERP).
- getERP(Vector3f) - Method in class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
Copy this motor's error-reduction parameters at the limits (native field: m_stopERP).
- getFallSpeed() - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Determine the character's maximum fall speed (terminal velocity).
- getFallSpeed() - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Determine this character's maximum fall speed (terminal velocity).
- getFillMode() - Method in class vhacd4.Vhacd4Parameters
-
Return the algorithm that fills voxels to create a solid object (native field: m_fillMode).
- getFinalHeight() - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Return the scaled height of the collision shape, including both hemispheres and the cylindrical part.
- getFinalRadius() - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Return the scaled radius of the collision shape.
- getFlags() - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Return the contact-point flags (native field: m_contactPointFlags).
- getFlags(long) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Return the flags of the specified point (native field: m_contactPointFlags).
- getForwardVector(Vector3f) - Method in class com.jme3.bullet.objects.infos.VehicleController
-
Determine the vehicle's forward direction.
- getForwardVector(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Determine this vehicle's forward direction.
- getFrameTransform(JointEnd, Transform) - Method in class com.jme3.bullet.joints.ConeJoint
-
Copy the joint's frame transform relative to the specified end.
- getFrameTransform(JointEnd, Transform) - Method in class com.jme3.bullet.joints.HingeJoint
-
Copy the joint's frame transform relative to the specified end.
- getFrameTransform(JointEnd, Transform) - Method in class com.jme3.bullet.joints.New6Dof
-
Copy the constraint's frame transform relative to the specified end (native fields: m_frameInA, m_frameInB).
- getFrameTransform(JointEnd, Transform) - Method in class com.jme3.bullet.joints.SixDofJoint
-
Copy the joint's frame transform relative to the specified end.
- getFrameTransform(JointEnd, Transform) - Method in class com.jme3.bullet.joints.SliderJoint
-
Copy the joint's frame transform relative to the specified end.
- getFriction() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Return the collision object's friction parameter (native field: m_friction).
- getFrictionSlip() - Method in class com.jme3.bullet.objects.infos.VehicleTuning
-
Return the friction between tires and ground (native field: m_frictionSlip).
- getFrictionSlip() - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Determine the initial friction for new wheels.
- getFrictionSlip() - Method in class com.jme3.bullet.objects.VehicleWheel
-
Determine the friction between this wheel's tire and the ground (native field: m_frictionSlip).
- getGhostObjectList() - Method in class com.jme3.bullet.CollisionSpace
-
Enumerate ghost objects that have been added to the space and not yet removed.
- getGravity(Vector3f) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Copy the character's gravity vector.
- getGravity(Vector3f) - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Determine the character's gravitational acceleration.
- getGravity(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsBody
-
Copy this body's gravitational acceleration.
- getGravity(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Determine this character's gravitational acceleration.
- getGravity(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Copy the body's gravitational acceleration.
- getGravity(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Copy this body's gravitational acceleration.
- getGravity(Vector3f) - Method in class com.jme3.bullet.PhysicsSpace
-
Copy the gravitational acceleration for newly-added bodies.
- getGravityDp(Vec3d) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Copy the body's gravitational acceleration.
- getHalfExtents(Vector3f) - Method in class com.jme3.bullet.collision.shapes.Box2dShape
-
Copy the half extents of the rectangle.
- getHalfExtents(Vector3f) - Method in class com.jme3.bullet.collision.shapes.BoxCollisionShape
-
Copy the half extents of the box.
- getHalfExtents(Vector3f) - Method in class com.jme3.bullet.collision.shapes.CylinderCollisionShape
-
Copy the half extents of the cylinder.
- getHalfExtents(Vector3f) - Method in class com.jme3.bullet.collision.shapes.HullCollisionShape
-
Calculate the unscaled half extents of the hull.
- getHalfExtents(Vector3f) - Method in class com.jme3.bullet.collision.shapes.SimplexCollisionShape
-
Calculate the unscaled half extents of the simplex.
- getHeight() - Method in class com.jme3.bullet.collision.shapes.CapsuleCollisionShape
-
Return the height of the cylindrical portion.
- getHeight() - Method in class com.jme3.bullet.collision.shapes.ConeCollisionShape
-
Return the height of the cone.
- getHeight() - Method in class com.jme3.bullet.collision.shapes.CylinderCollisionShape
-
Return the height of the cylinder.
- getHeight() - Method in class com.jme3.bullet.collision.shapes.SphericalSegment
-
Return the height of the segment.
- getHingeAngle() - Method in class com.jme3.bullet.joints.HingeJoint
-
Read the hinge angle.
- getHitFraction() - Method in class com.jme3.bullet.collision.PhysicsRayTestResult
-
Read the fraction of the ray's total length.
- getHitFraction() - Method in class com.jme3.bullet.collision.PhysicsSweepTestResult
-
Return the fraction of the way between the transforms (from=0, to=1, ≥0, ≤1)
- getHitNormalLocal() - Method in class com.jme3.bullet.collision.PhysicsRayTestResult
-
For compatibility with jme3-jbullet.
- getHitNormalLocal(Vector3f) - Method in class com.jme3.bullet.collision.PhysicsRayTestResult
-
Copy the normal vector at the point of contact.
- getHitNormalLocal(Vector3f) - Method in class com.jme3.bullet.collision.PhysicsSweepTestResult
-
Copy the normal vector at the point of contact.
- getImpulseClamp() - Method in class com.jme3.bullet.joints.Point2PointJoint
-
Return the joint's impulse clamp.
- getIndex() - Method in class com.jme3.bullet.objects.VehicleWheel
-
Determine the index of this wheel, based on creation order.
- getIndex0() - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Return the triangle index in the shape of object A at the point of contact (native field: m_index0).
- getIndex0(long) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Return the triangle index from the shape of object A at the specified point of contact (native field: m_index0).
- getIndex1() - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Return the triangle index in the shape of object B at the point of contact (native field: m_index1).
- getIndex1(long) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Return the triangle index from the shape of object B at the specified point of contact (native field: m_index1).
- getInitialHeight() - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Return the the initial height of the collision shape.
- getInitialRadius() - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Return the the initial radius of the collision shape.
- getInternalType(long) - Static method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Return the type of this object.
- getInverseInertiaLocal(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Copy the principal (diagonal) elements of the inverse inertia tensor in the body's local coordinates.
- getInverseInertiaWorld(Matrix3f) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Compute the inverse inertia tensor in physics-space coordinates.
- getJoint() - Method in class com.jme3.bullet.animation.PhysicsLink
-
Access the joint between this link's rigid body and that of its parent.
- getJointLimits(String) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Access the nominal range of motion for the joint connecting the named linked bone to its parent in the hierarchy.
- getJointList() - Method in class com.jme3.bullet.PhysicsSpace
-
Enumerate physics joints that have been added to the space and not yet removed.
- getJointMap() - Method in class com.jme3.bullet.PhysicsSpace
-
Access the map from native IDs to physics joints.
- getJumpForce(Vector3f) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Copy the impulse applied at the start of each jump.
- getJumpSpeed() - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Determine the character's jump speed.
- getJumpSpeed() - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Determine this character's jump speed.
- getLateralFrictionDir1(long, Vector3f) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Determine the lateral friction direction #1 of the specified point (native field: m_lateralFrictionDir1).
- getLateralFrictionDir1(Vector3f) - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Return the contact point's lateral friction direction #1 (native field: m_lateralFrictionDir1).
- getLateralFrictionDir2(long, Vector3f) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Determine the lateral friction direction #2 of the specified point (native field: m_lateralFrictionDir2).
- getLateralFrictionDir2(Vector3f) - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Return the contact point's lateral friction direction #2 (native field: m_lateralFrictionDir2).
- getLifeTime() - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Return the contact point's lifetime (native name: m_lifeTime).
- getLifeTime(long) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Return the lifetime of the specified point (native name: m_lifeTime).
- getLimitSoftness() - Method in class com.jme3.bullet.joints.HingeJoint
-
Read this joint's limit softness.
- getLimitSoftness() - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Return this motor's limit softness (native field: m_limitSoftness).
- getLimitSoftness() - Method in class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
Return this motor's limit softness (native field: m_limitSoftness).
- getLinearDamping() - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Determine the character's linear damping.
- getLinearDamping() - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Determine this character's linear damping.
- getLinearDamping() - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Return the body's linear damping.
- getLinearFactor(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Copy the body's linear factors.
- getLinearLowerLimit(Vector3f) - Method in class com.jme3.bullet.joints.SixDofJoint
-
Copy the joint's lower limits for translation on all 3 axes.
- getLinearSleepingThreshold() - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Return the body's linear-motion sleeping threshold.
- getLinearUpperLimit(Vector3f) - Method in class com.jme3.bullet.joints.SixDofJoint
-
Copy the joint's upper limits for translation on all 3 axes.
- getLinearVelocity() - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
For compatibility with the jme3-jbullet library.
- getLinearVelocity(Vector3f) - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Determine the linear velocity of the character's center.
- getLinearVelocity(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Determine the linear velocity of this character's center.
- getLinearVelocity(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Copy the linear velocity of the body's center of mass.
- getLinearVelocityDp(Vec3d) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Copy the linear velocity of the body's center of mass.
- getLink() - Method in class com.jme3.bullet.animation.IKController
-
Access the controlled link.
- getLink(int) - Method in class com.jme3.bullet.MultiBody
-
Access the index link of this MultiBody.
- getLocalPointA(long, Vector3f) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Determine the location of the specified point in the local coordinates of object A (native name: m_localPointA).
- getLocalPointA(Vector3f) - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Return the contact point's location in the local coordinates of object A (native name: m_localPointA).
- getLocalPointB(long, Vector3f) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Determine the location of the specified point in the local coordinates of object B (native name: m_localPointB).
- getLocalPointB(Vector3f) - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Return the contact point's location in the local coordinates of object B (native name: m_localPointB).
- getLocation() - Method in class com.jme3.bullet.objects.VehicleWheel
-
For compatibility with the jme3-jbullet library.
- getLocation(Vector3f) - Method in class com.jme3.bullet.objects.infos.RigidBodyMotionState
-
Copy the location to a Vector3f.
- getLocation(Vector3f) - Method in class com.jme3.bullet.objects.VehicleWheel
-
Determine the location where the suspension connects to the chassis.
- getLocationDp(Vec3d) - Method in class com.jme3.bullet.objects.infos.RigidBodyMotionState
-
Copy the location to a Vector3d.
- getLowerAngLimit() - Method in class com.jme3.bullet.joints.SliderJoint
-
Read the joint's lower limit for on-axis rotation.
- getLowerLimit() - Method in class com.jme3.bullet.joints.HingeJoint
-
Read the lower limit of the hinge angle.
- getLowerLimit() - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Return this motor's constraint lower limit (native field: m_loLimit).
- getLowerLimit(Vector3f) - Method in class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
Copy this motor's constraint lower limits (native field: m_lowerLimit).
- getLowerLinLimit() - Method in class com.jme3.bullet.joints.SliderJoint
-
Read the joint's lower limit for on-axis translation.
- getMargin() - Method in class com.jme3.bullet.collision.shapes.CapsuleCollisionShape
-
Return the collision margin of the shape.
- getMargin() - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Return the (copied) collision margin of the shape.
- getMargin() - Method in class com.jme3.bullet.collision.shapes.MinkowskiSum
-
Return the collision margin of this shape.
- getMargin() - Method in class com.jme3.bullet.collision.shapes.SphereCollisionShape
-
Return the collision margin of the shape.
- getMass() - Method in class com.jme3.bullet.objects.PhysicsBody
-
Determine the total mass of this body.
- getMass() - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Return the body's mass.
- getMass() - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Determine the total mass of this body.
- getMaxAngMotorForce() - Method in class com.jme3.bullet.joints.SliderJoint
-
Read the maximum force of the rotation motor.
- getMaxConcavity() - Method in class vhacd.VHACDParameters
-
Return the maximum concavity (native field: m_concavity).
- getMaxHulls() - Method in class vhacd4.Vhacd4Parameters
-
Return the maximum number of convex hulls (native field: m_maxConvexHulls).
- getMaxLimitForce() - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Return the limit maximum force (native field: m_maxLimitForce).
- getMaxLinMotorForce() - Method in class com.jme3.bullet.joints.SliderJoint
-
Read the maximum force of the translation motor.
- getMaxMotorForce() - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Return this motor's maximum force for normal conditions (native field: m_maxMotorForce).
- getMaxMotorForce(Vector3f) - Method in class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
Copy this motor's maximum motor forces for normal conditions (native field: m_maxMotorForce).
- getMaxMotorImpulse() - Method in class com.jme3.bullet.joints.HingeJoint
-
Read the motor's maximum impulse.
- getMaxPenetrationDepth() - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Determine the character's maximum penetration depth.
- getMaxPenetrationDepth() - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Determine this character's maximum penetration depth.
- getMaxRecursion() - Method in class vhacd4.Vhacd4Parameters
-
Return the maximum recursion depth (native field: m_maxRecursionDepth).
- getMaxRotation(int) - Method in class com.jme3.bullet.animation.RangeOfMotion
-
Read the maximum rotation around the indexed axis.
- getMaxSlope() - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Determine the character's maximum slope angle.
- getMaxSlope() - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Determine this character's maximum slope angle.
- getMaxSuspensionForce() - Method in class com.jme3.bullet.objects.infos.VehicleTuning
-
Return the maximum force exerted by each wheel's suspension (native field: m_maxSuspensionForce).
- getMaxSuspensionForce() - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Determine the initial maximum suspension force for new wheels.
- getMaxSuspensionForce() - Method in class com.jme3.bullet.objects.VehicleWheel
-
Determine the maximum force exerted by this wheel's suspension (native field: m_maxSuspensionForce).
- getMaxSuspensionTravelCm() - Method in class com.jme3.bullet.objects.infos.VehicleTuning
-
Determine the maximum travel distance for each wheel's suspension (native field: m_maxSuspensionTravelCm).
- getMaxSuspensionTravelCm() - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Determine the initial maximum suspension travel distance for new wheels.
- getMaxSuspensionTravelCm() - Method in class com.jme3.bullet.objects.VehicleWheel
-
Determine the maximum travel distance for this wheel's suspension (native field: m_maxSuspensionTravelCm).
- getMaxVerticesPerHull() - Method in class vhacd.VHACDParameters
-
Return the maximum number of vertices per convex hull (native field: m_maxNumVerticesPerCH).
- getMaxVerticesPerHull() - Method in class vhacd4.Vhacd4Parameters
-
Return the maximum number of vertices per convex hull (native field: m_maxNumVerticesPerCH).
- getMinEdgeLength() - Method in class vhacd4.Vhacd4Parameters
-
Return the minimum edge length (native field: m_minEdgeLength).
- getMinRotation(int) - Method in class com.jme3.bullet.animation.RangeOfMotion
-
Read the minimum rotation around the indexed axis.
- getMinVolumePerHull() - Method in class vhacd.VHACDParameters
-
Return the minimum volume for added vertices (native field: m_minVolumePerCH).
- getMotionState() - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Access the body's motion state.
- getMotorTargetVelocity() - Method in class com.jme3.bullet.joints.HingeJoint
-
Read the motor's target velocity.
- getMultiBody() - Method in class com.jme3.bullet.MultiBodyLink
-
Access the MultiBody that contains this link.
- getMultiBody() - Method in class com.jme3.bullet.objects.MultiBodyCollider
-
Access the MultiBody that contains this collider.
- getMultiBodyList() - Method in class com.jme3.bullet.MultiBodySpace
-
Enumerate multibodies that have been added to this space and not yet removed.
- getMultiBodySpace() - Method in class com.jme3.bullet.MultiBodyAppState
-
Access the space managed by this state.
- getMultiBodySpace() - Static method in class com.jme3.bullet.MultiBodySpace
-
Access the MultiBodySpace running on this thread.
- getNodeA() - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Access the user object of collision object A, provided it's a Spatial.
- getNodeB() - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Access the user object of collision object B, provided it's a Spatial.
- getNormalCFM() - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Return this motor's constraint-force mixing parameter for normal conditions (native field: m_normalCFM).
- getNormalCFM(Vector3f) - Method in class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
Copy this motor's constraint-force mixing parameters for normal conditions (native field: m_normalCFM).
- getNormalWorldOnB() - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
For compatibility with jme3-jbullet.
- getNormalWorldOnB(long, Vector3f) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Determine the normal on object B of the specified point in physics-space coordinates (native name: m_normalWorldOnB).
- getNormalWorldOnB(Vector3f) - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Return the contact point's normal on object B in physics-space coordinates (native name: m_normalWorldOnB).
- getNumWheels() - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Count the number of wheels on this vehicle.
- getObjectA() - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Access collision object A.
- getObjectB() - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Access collision object B.
- getOffset(Vector3f) - Method in class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
Return the offset of the constraint frames (native field: m_currentLinearDiff).
- getOrientation(Matrix3f) - Method in class com.jme3.bullet.objects.infos.RigidBodyMotionState
-
Copy the orientation to a Matrix3f.
- getOrientation(Quaternion) - Method in class com.jme3.bullet.objects.infos.RigidBodyMotionState
-
Copy the orientation to a Quaternion.
- getOrientationMatrixDp(Matrix3d) - Method in class com.jme3.bullet.objects.infos.RigidBodyMotionState
-
Copy the orientation to a Matrix3d.
- getOrientationQuaternionDp(Quatd) - Method in class com.jme3.bullet.objects.infos.RigidBodyMotionState
-
Copy the orientation to a Quatd.
- getOverlapping(int) - Method in class com.jme3.bullet.objects.PhysicsGhostObject
-
Access an overlapping collision object by its position in the list.
- getOverlappingCount() - Method in class com.jme3.bullet.objects.PhysicsGhostObject
-
Count how many collision objects this object overlaps.
- getOverlappingObjects() - Method in class com.jme3.bullet.objects.PhysicsGhostObject
-
Update and access a list of overlapping objects.
- getOverrideIterations() - Method in class com.jme3.bullet.joints.Constraint
-
Determine the number of iterations used to solve this Constraint.
- getParent() - Method in class com.jme3.bullet.animation.PhysicsLink
-
Access this link's parent/manager in the link hierarchy.
- getParentLink() - Method in class com.jme3.bullet.MultiBodyLink
-
Determine the parent of this link.
- getPartId0() - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Return the part index in the shape of object A at the point of contact (native field: m_partId0).
- getPartId0(long) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Return the part index from the shape of object A at the specified point of contact (native field: m_partId0).
- getPartId1() - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Return the part index in the shape of object B at the point of contact (native field: m_partId1).
- getPartId1(long) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Return the part index from the shape of object B at the specified point of contact (native field: m_partId1).
- getPCA() - Method in class vhacd.VHACDParameters
-
Test whether to normalize the mesh (native field: m_pca).
- getPcoList() - Method in class com.jme3.bullet.CollisionSpace
-
Enumerate collision objects that have been added to the space and not yet removed.
- getPcoList() - Method in class com.jme3.bullet.DeformableSpace
-
Enumerate collision objects that have been added to this space and not yet removed.
- getPcoList() - Method in class com.jme3.bullet.MultiBodySpace
-
Enumerate collision objects that have been added to this space and not yet removed.
- getPcoList() - Method in class com.jme3.bullet.PhysicsSoftSpace
-
Enumerate collision objects that have been added to this space and not yet removed.
- getPcoList() - Method in class com.jme3.bullet.PhysicsSpace
-
Enumerate collision objects that have been added to the space and not yet removed.
- getPcoMap() - Method in class com.jme3.bullet.debug.BulletDebugAppState
-
Access the map from collision objects to transformed visualization nodes.
- getPhysicsDamping() - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Return the damping factor for horizontal motion.
- getPhysicsJoint() - Method in class com.jme3.bullet.animation.IKJoint
-
Access the underlying Constraint.
- getPhysicsLocation() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
For compatibility with the jme3-jbullet library.
- getPhysicsLocation() - Method in class com.jme3.bullet.control.CharacterControl
-
Copy the character's location.
- getPhysicsLocation(Vector3f) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Locate the collision object's center.
- getPhysicsLocation(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Locate the center of this body's axis-aligned bounding box.
- getPhysicsLocationDp(Vec3d) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Locate the collision object's center in double precision.
- getPhysicsLocationDp(Vec3d) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Locate the center of this body's axis-aligned bounding box.
- getPhysicsRotation() - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
For compatibility with the jme3-jbullet library.
- getPhysicsRotation(Quaternion) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Copy the orientation (rotation) of the collision object to a Quaternion.
- getPhysicsRotation(Quaternion) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Copy the orientation (rotation) of this body to a Quaternion.
- getPhysicsRotationDp(Quatd) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Copy the orientation (rotation) of this object to a Quatd.
- getPhysicsRotationDp(Quatd) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Copy the orientation (rotation) of this body to a Quatd.
- getPhysicsRotationMatrix(Matrix3f) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Copy the orientation of the collision object (the basis of its local coordinate system) to a Matrix3f.
- getPhysicsRotationMatrix(Matrix3f) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Copy the orientation of this body (the basis of its local coordinate system) to a Matrix3f.
- getPhysicsRotationMatrixDp(Matrix3d) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Copy the orientation of the collision object (the basis of its local coordinate system) to a Matrix3d.
- getPhysicsRotationMatrixDp(Matrix3d) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Copy the orientation of this body (the basis of its local coordinate system) to a Matrix3d.
- getPhysicsSoftSpace() - Method in class com.jme3.bullet.SoftPhysicsAppState
-
Access the PhysicsSoftSpace managed by this state.
- getPhysicsSpace() - Method in class com.jme3.bullet.BulletAppState
-
Access the PhysicsSpace managed by this state.
- getPhysicsSpace() - Method in class com.jme3.bullet.control.AbstractPhysicsControl
-
Access the PhysicsSpace to which the object is (or would be) added.
- getPhysicsSpace() - Method in class com.jme3.bullet.control.GhostControl
-
Access the PhysicsSpace to which the ghost object is (or would be) added.
- getPhysicsSpace() - Method in interface com.jme3.bullet.control.PhysicsControl
-
Access the PhysicsSpace to which the physics objects are (or would be) added.
- getPhysicsSpace() - Method in class com.jme3.bullet.control.RigidBodyControl
-
Access the PhysicsSpace to which the body is (or would be) added.
- getPhysicsSpace() - Method in class com.jme3.bullet.control.VehicleControl
-
Access the PhysicsSpace to which the vehicle is (or would be) added.
- getPhysicsSpace() - Method in class com.jme3.bullet.joints.PhysicsJoint
-
Access the PhysicsSpace where this joint is added.
- getPhysicsSpace() - Static method in class com.jme3.bullet.PhysicsSpace
-
Access the PhysicsSpace running on this thread.
- getPivot(JointEnd, Vector3f) - Method in class com.jme3.bullet.joints.Constraint
-
Copy the location of the specified connection point in the specified body.
- getPivotA(Vector3f) - Method in class com.jme3.bullet.joints.Constraint
-
Copy the location of the connection point in the body at the A end.
- getPivotB(Vector3f) - Method in class com.jme3.bullet.joints.Constraint
-
Copy the location of the connection point in the body at the B end.
- getPivotOffset(Vector3f) - Method in class com.jme3.bullet.joints.New6Dof
-
Copy the constraint's pivot offset (native field: m_calculatedLinearDiff).
- getPivotOffset(Vector3f) - Method in class com.jme3.bullet.joints.SixDofJoint
-
Copy the joint's pivot offset.
- getPlane() - Method in class com.jme3.bullet.collision.shapes.PlaneCollisionShape
-
Copy the defining plane.
- getPlaneDownSampling() - Method in class vhacd.VHACDParameters
-
Return the granularity of the search (native field: m_planeDownsampling).
- getPointId(long, int) - Static method in class com.jme3.bullet.collision.PersistentManifolds
-
Return the indexed btManifoldPoint in the specified manifold.
- getPositionWorldOnA() - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
For compatibility with jme3-jbullet.
- getPositionWorldOnA(long, Vector3f) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Determine the location of the specified point on object A in physics-space coordinates (native field: m_positionWorldOnA).
- getPositionWorldOnA(Vector3f) - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Return the contact point's location on object A in physics-space coordinates (native field: m_positionWorldOnA).
- getPositionWorldOnADp(long, Vec3d) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Determine the location of the specified point on object A in physics-space coordinates (native field: m_positionWorldOnA).
- getPositionWorldOnB() - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
For compatibility with jme3-jbullet.
- getPositionWorldOnB(long, Vector3f) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Determine the location of the specified point on object B in physics-space coordinates (native field: m_positionWorldOnB).
- getPositionWorldOnB(Vector3f) - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Return the contact point's location on object B in physics-space coordinates (native field: m_positionWorldOnB).
- getPositionWorldOnBDp(long, Vec3d) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Determine the location of the specified point on object B in physics-space coordinates (native field: m_positionWorldOnB).
- getRadius() - Method in class com.jme3.bullet.collision.shapes.CapsuleCollisionShape
-
Return the radius of the capsule.
- getRadius() - Method in class com.jme3.bullet.collision.shapes.ConeCollisionShape
-
Return the radius of the cone's base.
- getRadius() - Method in class com.jme3.bullet.collision.shapes.SphereCollisionShape
-
Return the radius of the sphere.
- getRadius() - Method in class com.jme3.bullet.objects.VehicleWheel
-
Determine the radius of this wheel (native field: m_wheelsRadius).
- getRadius(int) - Method in class com.jme3.bullet.collision.shapes.MultiSphere
-
Return the radius of the indexed sphere.
- getRatio() - Method in class com.jme3.bullet.joints.GearJoint
-
Get the gear ratio.
- getRayTestFlags() - Method in class com.jme3.bullet.CollisionSpace
-
Return the flags used in ray tests (native field: m_flags).
- getRelaxationFactor() - Method in class com.jme3.bullet.joints.HingeJoint
-
Read this joint's relaxation factor.
- getRestitution() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Return the collision object's restitution (bounciness) (native field: m_restitution).
- getRestitution() - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Return this motor's restitution at the limits (native field: m_bounce).
- getRestitution() - Method in class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
Return this motor's restitution at the limits (native field: m_restitution).
- getRestitutionDirAng() - Method in class com.jme3.bullet.joints.SliderJoint
-
Read the joint's restitution for on-axis rotation between the limits.
- getRestitutionDirLin() - Method in class com.jme3.bullet.joints.SliderJoint
-
Read the joint's restitution for on-axis translation between the limits.
- getRestitutionLimAng() - Method in class com.jme3.bullet.joints.SliderJoint
-
Read the joint's restitution for on-axis rotation hitting the limits.
- getRestitutionLimLin() - Method in class com.jme3.bullet.joints.SliderJoint
-
Read the joint's restitution for on-axis translation hitting the limits.
- getRestitutionOrthoAng() - Method in class com.jme3.bullet.joints.SliderJoint
-
Read the joint's restitution for off-axis rotation.
- getRestitutionOrthoLin() - Method in class com.jme3.bullet.joints.SliderJoint
-
Read the joint's restitution for off-axis translation.
- getRestLength() - Method in class com.jme3.bullet.objects.VehicleWheel
-
Determine the rest length of this wheel (native field: m_suspensionRestLength1).
- getRigidBody() - Method in class com.jme3.bullet.animation.PhysicsLink
-
Access the linked rigid body.
- getRigidBody() - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Access the rigid body managed by this control.
- getRigidBody() - Method in class com.jme3.bullet.control.JoinedBodyControl
-
Access the rigid body managed by this Control.
- getRigidBody() - Method in class com.jme3.bullet.joints.Anchor
-
Access the rigid body at the B end.
- getRigidBodyList() - Method in class com.jme3.bullet.PhysicsSpace
-
Enumerate rigid bodies (including vehicles) that have been added to this space and not yet removed.
- getRollInfluence() - Method in class com.jme3.bullet.objects.VehicleWheel
-
Determine this wheel's roll influence (native field: m_rollInfluence).
- getRollingFriction() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Return this object's rolling friction (native field: m_rollingFriction).
- getRootNode() - Method in class com.jme3.bullet.debug.BulletDebugAppState
-
Access the Node containing all the debug visualization.
- getRotationalLimitMotor(int) - Method in class com.jme3.bullet.joints.SixDofJoint
-
Access the indexed RotationalLimitMotor of this joint, the motor which influences rotation around the indexed axis.
- getRotationAngle() - Method in class com.jme3.bullet.objects.VehicleWheel
-
Determine the total rotation of this wheel (native field: m_rotation).
- getRotationMatrix(JointEnd, Matrix3f) - Method in class com.jme3.bullet.joints.New6Dof
-
Copy the orientation of the constraint in the specified end's coordinate system.
- getRotationMotor(int) - Method in class com.jme3.bullet.joints.New6Dof
-
Access the indexed RotationMotor of this constraint, the motor which influences rotation around the indexed axis.
- getRotationOrder() - Method in class com.jme3.bullet.joints.New6Dof
-
Return the order in which axis rotations are applied (native field: m_rotateOrder).
- getScale(Vector3f) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Copy the scale of this object.
- getScale(Vector3f) - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Copy the scale factors.
- getScale(Vector3f) - Method in class com.jme3.bullet.collision.shapes.infos.CompoundMesh
-
Copy the scale factors.
- getScale(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Copy the scale factors of this object.
- getScaleDp(Vec3d) - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Copy the scale factors.
- getShape() - Method in class com.jme3.bullet.collision.shapes.infos.ChildCollisionShape
-
Access the base shape.
- getShape() - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Create a CollisionShape based on the
scale
parameter. - getShapeA() - Method in class com.jme3.bullet.collision.shapes.MinkowskiSum
-
Access the first base shape.
- getShapeB() - Method in class com.jme3.bullet.collision.shapes.MinkowskiSum
-
Access the 2nd base shape.
- getShapeType() - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Return the encoded type of the shape.
- getShapeType(long) - Static method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Return the type of this shape.
- getSkeleton() - Method in class com.jme3.bullet.animation.DacLinks
-
Access the Skeleton.
- getSkidInfo() - Method in class com.jme3.bullet.objects.VehicleWheel
-
Determine to what extent the wheel is skidding (for skid sounds/smoke etcetera).
- getSoftBody() - Method in class com.jme3.bullet.joints.Anchor
-
Access the soft body at the A end.
- getSoftBodyA() - Method in class com.jme3.bullet.joints.SoftPhysicsJoint
-
Access the soft body at the A end.
- getSoftBodyB() - Method in class com.jme3.bullet.joints.SoftPhysicsJoint
-
Access the soft body at the B end.
- getSoftBodyList() - Method in class com.jme3.bullet.DeformableSpace
-
Enumerate soft bodies that have been added to this space and not yet removed.
- getSoftBodyList() - Method in class com.jme3.bullet.PhysicsSoftSpace
-
Enumerate soft bodies that have been added to this space and not yet removed.
- getSoftConfig() - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Access the SoftBodyConfig of this body.
- getSoftMaterial() - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Access the Material of this body.
- getSoftnessDirAng() - Method in class com.jme3.bullet.joints.SliderJoint
-
Read the joint's softness for on-axis rotation between the limits.
- getSoftnessDirLin() - Method in class com.jme3.bullet.joints.SliderJoint
-
Read the joint's softness for on-axis translation between the limits.
- getSoftnessLimAng() - Method in class com.jme3.bullet.joints.SliderJoint
-
Read the joint's softness for on-axis rotation hitting the limits.
- getSoftnessLimLin() - Method in class com.jme3.bullet.joints.SliderJoint
-
Read the joint's softness for on-axis translation hitting the limits.
- getSoftnessOrthoAng() - Method in class com.jme3.bullet.joints.SliderJoint
-
Read the joint's softness for off-axis rotation.
- getSoftnessOrthoLin() - Method in class com.jme3.bullet.joints.SliderJoint
-
Read the joint's softness for off-axis translation.
- getSoftSpace() - Static method in class com.jme3.bullet.PhysicsSoftSpace
-
Access the PhysicsSoftSpace running on this thread.
- getSolverInfo() - Method in class com.jme3.bullet.PhysicsSpace
-
Access parameters used by the contact-and-constraint solver.
- getSolverNumIterations() - Method in class com.jme3.bullet.PhysicsSpace
-
Return the number of iterations used by the contact-and-constraint solver, for compatibility with the jme3-jbullet library.
- getSolverType() - Method in class com.jme3.bullet.BulletAppState
-
Determine which constraint solver the PhysicsSpace will use.
- getSolverType() - Method in class com.jme3.bullet.PhysicsSpace
-
Return the type of contact-and-constraint solver in use.
- getSpace() - Method in class com.jme3.bullet.debug.DebugConfiguration
-
Access the PhysicsSpace.
- getSpatial() - Method in class com.jme3.bullet.control.AbstractPhysicsControl
-
Access the Spatial to which this Control is added.
- getSpatial() - Method in class com.jme3.bullet.control.GhostControl
-
Access the controlled Spatial.
- getSpatial() - Method in class com.jme3.bullet.control.RigidBodyControl
-
Access the controlled spatial.
- getSpatial() - Method in class com.jme3.bullet.control.VehicleControl
-
Access the controlled Spatial.
- getSpatialRotation() - Method in class com.jme3.bullet.control.AbstractPhysicsControl
-
Access whichever (spatial) rotation corresponds to the physics rotation.
- getSpatialTranslation() - Method in class com.jme3.bullet.control.AbstractPhysicsControl
-
Access whichever (spatial) translation corresponds to the physics location.
- getSpeed() - Method in class com.jme3.bullet.BulletAppState
-
Return the physics-simulation speed.
- getSpinningFriction() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Return this object's spinning friction (native field: m_spinningFriction).
- getSplit() - Method in class com.jme3.bullet.joints.SoftPhysicsJoint
-
Return the split.
- getSquaredSpeed() - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Calculate the squared speed of the body.
- getSteerAngle() - Method in class com.jme3.bullet.objects.VehicleWheel
-
Determine this wheel's steering angle (native field: m_steering).
- getStepHeight() - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Determine the character's step height.
- getStepHeight() - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Determine this character's step height.
- getStiffness(int) - Method in class com.jme3.bullet.joints.SixDofSpringJoint
-
Return the spring stiffness of the indexed degree of freedom.
- getStopCFM() - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Return this motor's constraint-force mixing parameter at the limits (native field: m_stopCFM).
- getStopCFM(Vector3f) - Method in class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
Copy this motor's constraint-force mixing parameters at the limits (native field: m_stopCFM).
- getSubmesh(int) - Method in class com.jme3.bullet.collision.shapes.GImpactCollisionShape
-
Access the specified submesh.
- getSubmesh(int) - Method in class com.jme3.bullet.collision.shapes.infos.CompoundMesh
-
Access the specified submesh.
- getSubmesh(int) - Method in class com.jme3.bullet.collision.shapes.MeshCollisionShape
-
Access the specified submesh.
- getSuspensionCompression() - Method in class com.jme3.bullet.objects.infos.VehicleTuning
-
Return the suspension damping when compressed (native field: m_suspensionCompression).
- getSuspensionCompression() - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Determine the initial damping (when the suspension is compressed) for new wheels.
- getSuspensionDamping() - Method in class com.jme3.bullet.objects.infos.VehicleTuning
-
Return the suspension damping when expanded (native field: m_suspensionDamping).
- getSuspensionDamping() - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Determine the initial damping (when the suspension is expanded) for new wheels.
- getSuspensionLength() - Method in class com.jme3.bullet.objects.VehicleWheel
-
Determine the length of this wheel's suspension (native field: m_suspensionLength).
- getSuspensionStiffness() - Method in class com.jme3.bullet.objects.infos.VehicleTuning
-
Return the suspension stiffness (native field: m_suspensionStiffness).
- getSuspensionStiffness() - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Determine the initial suspension stiffness for new wheels.
- getSuspensionStiffness() - Method in class com.jme3.bullet.objects.VehicleWheel
-
Determine the stiffness of this wheel's suspension (native field: m_suspensionStiffness).
- getSwingSpan1() - Method in class com.jme3.bullet.joints.ConeJoint
-
Return the span of the first swing axis.
- getSwingSpan2() - Method in class com.jme3.bullet.joints.ConeJoint
-
Return the span of the 2nd swing axis.
- getTargetAngMotorVelocity() - Method in class com.jme3.bullet.joints.SliderJoint
-
Read the velocity target of the rotation motor.
- getTargetLinMotorVelocity() - Method in class com.jme3.bullet.joints.SliderJoint
-
Read the velocity target of the translation motor.
- getTargetVelocity() - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Return this motor's target velocity (native field: m_targetVelocity).
- getTargetVelocity(Vector3f) - Method in class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
Copy this motor's target velocity (native field: m_targetVelocity).
- getTau() - Method in class com.jme3.bullet.joints.Point2PointJoint
-
Return the joint's tau value.
- getThreadingType() - Method in class com.jme3.bullet.BulletAppState
-
Determine which type of threading this app state uses.
- getTorsoLink() - Method in class com.jme3.bullet.animation.DacLinks
-
Access the TorsoLink.
- getTransform(Transform) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Copy the coordinate transform of this object, including the scale of its shape.
- getTransformer() - Method in class com.jme3.bullet.animation.DacLinks
-
Access the Spatial with the mesh-coordinate transform.
- getTransformSpatial() - Method in class com.jme3.bullet.debug.DebugConfiguration
-
Access the Spatial used to convert physics-space coordinates into world coordinates.
- getTranslationalLimitMotor() - Method in class com.jme3.bullet.joints.SixDofJoint
-
Access the TranslationalLimitMotor of this joint, the motor which influences translation on all 3 axes.
- getTranslationMotor() - Method in class com.jme3.bullet.joints.New6Dof
-
Access the TranslationMotor of this Constraint, the motor which influences translation on all 3 axes.
- getTuning() - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Access the tuning parameters applied when a wheel is created.
- getTwistSpan() - Method in class com.jme3.bullet.joints.ConeJoint
-
Return the span of the twist (local X) axis.
- getUpDirection(Vector3f) - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Determine the character's "up" direction.
- getUpDirection(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Determine this character's "up" direction.
- getUpperAngLimit() - Method in class com.jme3.bullet.joints.SliderJoint
-
Read the joint's upper limit for on-axis rotation.
- getUpperLimit() - Method in class com.jme3.bullet.joints.HingeJoint
-
Read the upper limit of the hinge angle.
- getUpperLimit() - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Return this motor's constraint upper limit (native field: m_hiLimit).
- getUpperLimit(Vector3f) - Method in class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
Copy this motor's constraint upper limits (native field: m_upperLimit).
- getUpperLinLimit() - Method in class com.jme3.bullet.joints.SliderJoint
-
Read the joint's upper limit for on-axis translation.
- getUserObject() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Access the scene object that's using the collision object, typically a PhysicsControl, PhysicsLink, or Spatial.
- getVehicleId() - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Used internally.
- getVehicleList() - Method in class com.jme3.bullet.PhysicsSpace
-
Enumerate physics vehicles that have been added to the space and not yet removed.
- getVelocity() - Method in class com.jme3.bullet.control.BetterCharacterControl
-
For compatibility with the jme3-jbullet library.
- getVelocity(Vector3f) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Copy the character's linear velocity.
- getViewDirection() - Method in class com.jme3.bullet.control.BetterCharacterControl
-
For compatibility with the jme3-jbullet library.
- getViewDirection(Vector3f) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Copy the character's view direction.
- getViewDirection(Vector3f) - Method in class com.jme3.bullet.control.CharacterControl
-
Copy the character's view direction.
- getVolumePercentError() - Method in class vhacd4.Vhacd4Parameters
-
Return the tolerance for the percent difference between the voxel volume and the volume of the hull (native field: m_minimumVolumePercentErrorAllowed).
- getVoxelResolution() - Method in class vhacd.VHACDParameters
-
Return the maximum number of voxels generated during the voxelization stage (native field: m_resolution).
- getVoxelResolution() - Method in class vhacd4.Vhacd4Parameters
-
Return the maximum number of voxels generated during the voxelization stage (native field: m_resolution).
- getWalkDirection(Vector3f) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Copy the character's walk velocity.
- getWalkDirection(Vector3f) - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Determine the character's walk offset.
- getWalkDirection(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Determine the character's walk offset.
- getWheel(int) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Access the indexed wheel of this vehicle.
- getWheelsDampingCompression() - Method in class com.jme3.bullet.objects.VehicleWheel
-
Determine this wheel's damping when the suspension is compressed (native field: m_wheelsDampingCompression).
- getWheelsDampingRelaxation() - Method in class com.jme3.bullet.objects.VehicleWheel
-
Determine this wheel's damping when the suspension is expanded (native field: m_wheelsDampingRelaxation).
- getWheelSpatial() - Method in class com.jme3.bullet.objects.VehicleWheel
-
Access the scene-graph subtree used to visualize this wheel.
- getWheelWorldLocation(Vector3f) - Method in class com.jme3.bullet.objects.VehicleWheel
-
Determine this wheel's location.
- getWheelWorldRotation(Quaternion) - Method in class com.jme3.bullet.objects.VehicleWheel
-
Determine this wheel's orientation.
- getWorldInfo() - Method in class com.jme3.bullet.DeformableSpace
-
Access the parameters applied when soft bodies are added to this space.
- getWorldInfo() - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Access the world info.
- getWorldInfo() - Method in class com.jme3.bullet.PhysicsSoftSpace
-
Access the parameters applied when soft bodies are added to this space.
- getWorldMax(Vector3f) - Method in class com.jme3.bullet.CollisionSpace
-
Copy the maximum coordinate values for the space.
- getWorldMin(Vector3f) - Method in class com.jme3.bullet.CollisionSpace
-
Copy the minimum coordinate values for the space.
- getWorldType(long) - Static method in class com.jme3.bullet.PhysicsSpace
-
Determine the type of the underlying btDynamicsWorld.
- ghost - Static variable in class com.jme3.bullet.collision.PcoType
-
value for a PhysicsGhostObject (native name: CO_GHOST_OBJECT)
- GhostControl - Class in com.jme3.bullet.control
-
A PhysicsControl to link a PhysicsGhostObject to a Spatial.
- GhostControl() - Constructor for class com.jme3.bullet.control.GhostControl
-
No-argument constructor needed by SavableClassUtil.
- GhostControl(CollisionShape) - Constructor for class com.jme3.bullet.control.GhostControl
-
Instantiate an enabled Control with the specified CollisionShape.
- GImpactCollisionShape - Class in com.jme3.bullet.collision.shapes
-
A mesh collisions shape based on Bullet's
btGImpactMeshShape
. - GImpactCollisionShape() - Constructor for class com.jme3.bullet.collision.shapes.GImpactCollisionShape
-
No-argument constructor needed by SavableClassUtil.
- GImpactCollisionShape(CompoundMesh, Vector3f) - Constructor for class com.jme3.bullet.collision.shapes.GImpactCollisionShape
-
Instantiate a shape based on the specified CompoundMesh and offset.
- GImpactCollisionShape(IndexedMesh...) - Constructor for class com.jme3.bullet.collision.shapes.GImpactCollisionShape
-
Instantiate a shape based on the specified native mesh(es).
- GImpactCollisionShape(Mesh...) - Constructor for class com.jme3.bullet.collision.shapes.GImpactCollisionShape
-
Instantiate a shape based on the specified JME mesh(es).
- GjkRaytest - Static variable in class com.jme3.bullet.RayTestFlag
-
use the GJK algorithm for ray-versus-convex intersection (native value: kF_UseGjkConvexCastRaytest)
- globalCfm() - Method in class com.jme3.bullet.SolverInfo
-
Determine the global constraint-force mixing parameter (native field: m_globalCfm).
- gravity(Vector3f) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Copy this control's gravitational acceleration for Ragdoll mode.
H
- halfExtents(CollisionShape, Vector3f) - Static method in class jme3utilities.minie.MyShape
-
Determine the unscaled half extents of the specified shape.
- HAS_COLLISION_SOUND_TRIGGER - Static variable in class com.jme3.bullet.collision.CollisionFlag
-
flag not supported by Minie
- HAS_CONTACT_CFM - Static variable in class com.jme3.bullet.collision.ContactPointFlag
-
contact has a constraint-force modifier
- HAS_CONTACT_ERP - Static variable in class com.jme3.bullet.collision.ContactPointFlag
-
contact has an error-reduction parameter
- HAS_CONTACT_STIFFNESS_DAMPING - Static variable in class com.jme3.bullet.collision.CollisionFlag
-
indicates that contact damping and/or contact stiffness have been set
- HAS_CUSTOM_DEBUG_RENDERING_COLOR - Static variable in class com.jme3.bullet.collision.CollisionFlag
-
flag not supported by Minie: use
PhysicsCollisionObject.setDebugMaterial(com.jme3.material.Material)
instead - HAS_FRICTION_ANCHOR - Static variable in class com.jme3.bullet.collision.CollisionFlag
-
flag not supported by Minie
- hasAnisotropicFriction(int) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Test whether the collision object has anisotropic friction.
- hasAssignedNativeObject() - Method in class com.jme3.bullet.NativePhysicsObject
-
Test whether a native object is assigned to this instance.
- hasAttachmentLink(String) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Test whether an AttachmentLink exists for the named bone.
- hasBoneLink(String) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Test whether a BoneLink exists for the named bone.
- hasClosest(CollisionShape, CollisionShape) - Method in class com.jme3.bullet.CollisionSpace
-
Test whether a nontrivial closest-points algorithm is registered for the specified collision shapes.
- hasContact(CollisionShape, CollisionShape) - Method in class com.jme3.bullet.CollisionSpace
-
Test whether a nontrivial contact-points algorithm is registered for the specified collision shapes.
- hasFixedBase() - Method in class com.jme3.bullet.MultiBody
-
Test whether this MultiBody has a fixed base.
- hashCode() - Method in class com.jme3.bullet.animation.LinkConfig
-
Generate the hash code for this LinkConfig.
- hashCode() - Method in class com.jme3.bullet.NativePhysicsObject
-
Return the hash code for this instance.
- hashCode() - Method in class vhacd.VHACDParameters
-
Generate the hash code for this instance.
- hashCode() - Method in class vhacd4.Vhacd4Parameters
-
Generate the hash code for this instance.
- hasShapeChanged(CollisionShape) - Method in class com.jme3.bullet.debug.BulletCharacterDebugControl
-
Compare the specified CollisionShape with the lastShape.
- height() - Method in class com.jme3.bullet.collision.shapes.ConicalFrustum
-
Return the height of the frustum.
- height(CollisionShape) - Static method in class jme3utilities.minie.MyShape
-
Determine the unscaled height of the specified shape.
- HeightfieldCollisionShape - Class in com.jme3.bullet.collision.shapes
-
A collision shape for terrain defined by a matrix of height values, based on Bullet's
btHeightfieldTerrainShape
. - HeightfieldCollisionShape() - Constructor for class com.jme3.bullet.collision.shapes.HeightfieldCollisionShape
-
No-argument constructor needed by SavableClassUtil.
- HeightfieldCollisionShape(float[]) - Constructor for class com.jme3.bullet.collision.shapes.HeightfieldCollisionShape
-
Instantiate a square shape for the specified array of heights.
- HeightfieldCollisionShape(float[], Vector3f) - Constructor for class com.jme3.bullet.collision.shapes.HeightfieldCollisionShape
-
Instantiate a square shape for the specified height map and scale vector.
- HeightfieldCollisionShape(int, int, float[], Vector3f, int, boolean, boolean, boolean, boolean) - Constructor for class com.jme3.bullet.collision.shapes.HeightfieldCollisionShape
-
Instantiate a rectangular shape for the specified parameters.
- HeightfieldCollisionShape(HeightMap) - Constructor for class com.jme3.bullet.collision.shapes.HeightfieldCollisionShape
-
Instantiate a square shape for the specified HeightMap.
- HeightfieldCollisionShape(Terrain, Vector3f) - Constructor for class com.jme3.bullet.collision.shapes.HeightfieldCollisionShape
-
Instantiate a square shape for the specified terrain and scale vector.
- highResolution - Static variable in class com.jme3.bullet.util.DebugShapeFactory
-
specify high-resolution debug meshes for convex shapes (up to 256 vertices) and zero-margin debug meshes for concave shapes
- highResolution2 - Static variable in class com.jme3.bullet.util.DebugShapeFactory
-
specify high-resolution debug meshes for convex shapes (up to 256 vertices) and actual-margin debug meshes for concave shapes
- HingeJoint - Class in com.jme3.bullet.joints
-
A single degree-of-freedom joint based on Bullet's btHingeConstraint.
- HingeJoint() - Constructor for class com.jme3.bullet.joints.HingeJoint
-
No-argument constructor needed by SavableClassUtil.
- HingeJoint(PhysicsRigidBody, PhysicsRigidBody, Vector3f, Vector3f, Vector3f, Vector3f) - Constructor for class com.jme3.bullet.joints.HingeJoint
-
Instantiate a double-ended HingeJoint.
- HingeJoint(PhysicsRigidBody, Vector3f, Vector3f, Vector3f, Vector3f, JointEnd) - Constructor for class com.jme3.bullet.joints.HingeJoint
-
Instantiate a single-ended HingeJoint.
- HullCollisionShape - Class in com.jme3.bullet.collision.shapes
-
A convex-hull collision shape based on Bullet's
btConvexHullShape
. - HullCollisionShape() - Constructor for class com.jme3.bullet.collision.shapes.HullCollisionShape
-
No-argument constructor needed by SavableClassUtil.
- HullCollisionShape(float...) - Constructor for class com.jme3.bullet.collision.shapes.HullCollisionShape
-
Instantiate a shape based on the specified array of coordinates.
- HullCollisionShape(Vector3f...) - Constructor for class com.jme3.bullet.collision.shapes.HullCollisionShape
-
Instantiate a shape based on the specified array of locations.
- HullCollisionShape(Mesh...) - Constructor for class com.jme3.bullet.collision.shapes.HullCollisionShape
-
Instantiate a shape based on the specified JME mesh(es).
- HullCollisionShape(FloatBuffer) - Constructor for class com.jme3.bullet.collision.shapes.HullCollisionShape
-
Instantiate a shape based on a flipped buffer containing coordinates.
- HullCollisionShape(Collection<Vector3f>) - Constructor for class com.jme3.bullet.collision.shapes.HullCollisionShape
-
Instantiate a shape based on the specified collection of locations.
- HullCollisionShape(RectangularSolid) - Constructor for class com.jme3.bullet.collision.shapes.HullCollisionShape
-
Instantiate an 8-vertex shape to match the specified rectangular solid.
- HullCollisionShape(VHACDHull) - Constructor for class com.jme3.bullet.collision.shapes.HullCollisionShape
-
Instantiate a shape based on a VHACDHull.
- HullCollisionShape(Vhacd4Hull) - Constructor for class com.jme3.bullet.collision.shapes.HullCollisionShape
-
Instantiate a shape based on a Vhacd4Hull.
I
- Ignore - Enum constant in enum class com.jme3.bullet.control.UseTriangles
-
ignore triangle indices
- ignoredHops() - Method in class com.jme3.bullet.animation.DacConfiguration
-
Determine the maximum number of physics-joint hops across which bodies ignore collisions.
- ignores(PhysicsCollisionObject) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Test whether the specified collision object is in the current collision object's ignore list.
- Ignores - Enum constant in enum class jme3utilities.minie.DumpFlags
-
ignored objects in collision objects
- IKController - Class in com.jme3.bullet.animation
-
An abstract inverse kinematics (IK) controller for a PhysicsLink in dynamic mode.
- IKController() - Constructor for class com.jme3.bullet.animation.IKController
-
No-argument constructor needed by SavableClassUtil.
- IKController(PhysicsLink) - Constructor for class com.jme3.bullet.animation.IKController
-
Instantiate an enabled controller.
- IKJoint - Class in com.jme3.bullet.animation
-
A Constraint used for inverse kinematics (as opposed to joining bones and/or attachments).
- IKJoint() - Constructor for class com.jme3.bullet.animation.IKJoint
-
No-argument constructor needed by SavableClassUtil.
- IKJoint(Constraint, boolean) - Constructor for class com.jme3.bullet.animation.IKJoint
-
Instantiate a new IK joint.
- index() - Method in class com.jme3.bullet.MultiBodyLink
-
Determine the index of this link in its MultiBody.
- IndexedMesh - Class in com.jme3.bullet.collision.shapes.infos
-
An indexed triangle mesh based on Bullet's
btIndexedMesh
. - IndexedMesh() - Constructor for class com.jme3.bullet.collision.shapes.infos.IndexedMesh
-
No-argument constructor needed by SavableClassUtil.
- IndexedMesh(CollisionShape, int) - Constructor for class com.jme3.bullet.collision.shapes.infos.IndexedMesh
-
Instantiate a IndexedMesh to visualize the specified collision shape.
- IndexedMesh(CollisionShape, int, boolean) - Constructor for class com.jme3.bullet.collision.shapes.infos.IndexedMesh
-
Instantiate an IndexedMesh from the debug mesh of the specified CollisionShape.
- IndexedMesh(Vector3f[], int[]) - Constructor for class com.jme3.bullet.collision.shapes.infos.IndexedMesh
-
Instantiate an IndexedMesh based on the specified positions and indices.
- IndexedMesh(Mesh) - Constructor for class com.jme3.bullet.collision.shapes.infos.IndexedMesh
-
Instantiate an IndexedMesh based on the specified JME mesh, without transforming coordinates.
- IndexedMesh(Mesh, Transform) - Constructor for class com.jme3.bullet.collision.shapes.infos.IndexedMesh
-
Instantiate an IndexedMesh based on the specified JME mesh and coordinate transform.
- IndexedMesh(FloatBuffer) - Constructor for class com.jme3.bullet.collision.shapes.infos.IndexedMesh
-
Instantiate an IndexedMesh based on the specified vertex positions.
- IndexedMesh(FloatBuffer, IntBuffer) - Constructor for class com.jme3.bullet.collision.shapes.infos.IndexedMesh
-
Instantiate an IndexedMesh based on the specified positions and indices.
- inertia(Vector3f) - Method in class com.jme3.bullet.MultiBodyLink
-
Determine the rotational inertia of this link.
- influence() - Method in class com.jme3.bullet.joints.Anchor
-
Return how much influence the anchor has on the bodies.
- initDefault() - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Reinitialize the btSoftBody to the default values.
- initialize(Application) - Method in class com.jme3.bullet.debug.BulletDebugAppState
-
Initialize this state prior to its first update.
- initialize(Application) - Method in class com.jme3.bullet.debug.DebugConfiguration
-
Set the camera and viewport based on the specified Application, unless they've already been set.
- initialize(AppStateManager, Application) - Method in class com.jme3.bullet.BulletAppState
-
Initialize this state prior to its first update.
- initSolverInfo() - Method in class com.jme3.bullet.PhysicsSpace
-
Initialize the solverInfo field during create().
- initThread(long) - Method in class com.jme3.bullet.CollisionSpace
-
Must be invoked on the designated physics thread.
- initUserPointer() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
(Re-)initialize the native user info of this collision object, which stores the collision group, collide-with groups, and spaceId (native field: m_userPointer).
- installMeshCustomizer(MeshCustomizer) - Static method in class com.jme3.bullet.util.DebugShapeFactory
-
Install the specified MeshCustomizer, replacing any customizer previously installed.
- Interleave - Static variable in class com.jme3.bullet.SolverMode
-
interleave contact and friction constraints
- isActive() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Test whether the collision object has been deactivated due to lack of motion.
- isAllowCollision() - Method in class com.jme3.bullet.joints.Anchor
-
Test whether collisions are allowed between the bodies.
- isAngularOnly() - Method in class com.jme3.bullet.joints.ConeJoint
-
Test whether this joint is angular-only.
- isAngularOnly() - Method in class com.jme3.bullet.joints.HingeJoint
-
Test whether this joint is angular-only, meaning no constraints on translation.
- isApplyLocal() - Method in class com.jme3.bullet.objects.VehicleWheel
-
Test whether physics coordinates should match the local transform of the Spatial.
- isApplyPhysicsLocal() - Method in class com.jme3.bullet.control.AbstractPhysicsControl
-
Test whether physics-space coordinates should match the spatial's local coordinates.
- isApplyPhysicsLocal() - Method in class com.jme3.bullet.control.GhostControl
-
Test whether physics-space coordinates should match the spatial's local coordinates.
- isApplyPhysicsLocal() - Method in class com.jme3.bullet.control.RigidBodyControl
-
Test whether physics-space coordinates should match the spatial's local coordinates.
- isApplyPhysicsLocal() - Method in class com.jme3.bullet.control.VehicleControl
-
Test whether physics-space coordinates should match the spatial's local coordinates.
- isApplyPhysicsLocal() - Method in class com.jme3.bullet.objects.infos.RigidBodyMotionState
-
Test whether physics-space coordinates should match the spatial's local coordinates.
- isApplyPhysicsLocal(Control) - Static method in class jme3utilities.minie.MyControlP
-
Test whether the specified SGC applies physics coordinates to its spatial's local translation.
- isApplyScale() - Method in class com.jme3.bullet.control.GhostControl
-
Test whether the collision-shape scale should match the spatial's scale.
- isApplyScale() - Method in class com.jme3.bullet.control.RigidBodyControl
-
Test whether the collision-shape scale should match the spatial's scale.
- isAsync() - Method in class vhacd4.Vhacd4Parameters
-
Test whether V-HACD should run on a new thread (native field: m_asyncACD).
- isCcdWithStaticOnly() - Method in class com.jme3.bullet.PhysicsSpace
-
Test whether CCD checks for collisions with static and kinematic bodies (native field: m_ccdWithStaticOnly).
- isCollisionAllowed(long) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Test whether collisions are allowed between this body and the identified collision object.
- isCollisionBetweenLinkedBodies() - Method in class com.jme3.bullet.joints.Constraint
-
Test whether collisions are handled between the ends.
- isCollisionWithParent() - Method in class com.jme3.bullet.MultiBodyLink
-
Test whether collisions with the immediate parent link are enabled.
- isCompressed() - Method in class com.jme3.bullet.collision.shapes.infos.BoundingValueHierarchy
-
Test whether the hierarchy uses quantized AABB compression.
- isConcave() - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Test whether the shape has concave type.
- isConcave() - Method in class com.jme3.bullet.collision.shapes.ConvexShape
-
Test whether this shape has concave type.
- isContactCalcArea3Points() - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Determine how many points are used to calculate the area of the convex hull of a contact point.
- isContactFilterEnabled() - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Test whether contact filtering is enabled for this shape.
- isContactResponse() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Test whether the collision object responds to contact with other objects.
- isControlEnabled(Control) - Method in class jme3utilities.minie.PhysicsDescriber
-
Test whether a scene-graph control is enabled.
- isConvex() - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Test whether the shape has convex type.
- isConvex() - Method in class com.jme3.bullet.collision.shapes.ConvexShape
-
Test whether this shape has convex type.
- isDampingLimited() - Method in class com.jme3.bullet.joints.motors.RotationMotor
-
Test whether the spring's damping is limited (native field: m_springDampingLimited).
- isDampingLimited(int) - Method in class com.jme3.bullet.joints.motors.TranslationMotor
-
Test whether the indexed spring's damping is limited (m_springDampingLimited).
- isDeactivationEnabled() - Static method in class com.jme3.bullet.objects.PhysicsBody
-
Test the global deactivation enable flag.
- isDebug() - Static method in class com.jme3.bullet.util.NativeLibrary
-
Test whether the native library was built with debugging enabled.
- isDebugEnabled() - Method in class com.jme3.bullet.BulletAppState
-
Test whether debug visualization is enabled.
- isDisableForRagdoll() - Method in class com.jme3.bullet.animation.IKJoint
-
Test whether to disable the Constraint when entering ragdoll mode.
- isDoublePrecision() - Static method in class com.jme3.bullet.util.NativeLibrary
-
Test whether the native library uses double-precision arithmetic.
- isDucked() - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Determine whether the character is in a ducked state, either due to user input or because an overhead obstacle prevents it from unducking.
- isDynamic() - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Test whether the body is in dynamic mode.
- isEmpty() - Method in class com.jme3.bullet.CollisionSpace
-
Test whether the space is empty.
- isEmpty() - Method in class com.jme3.bullet.DeformableSpace
-
Test whether this space is empty.
- isEmpty() - Method in class com.jme3.bullet.MultiBodySpace
-
Test whether this space is empty.
- isEmpty() - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Test whether this body is empty.
- isEmpty() - Method in class com.jme3.bullet.PhysicsSoftSpace
-
Test whether this space is empty.
- isEmpty() - Method in class com.jme3.bullet.PhysicsSpace
-
Test whether the space is empty.
- isEnabled() - Method in class com.jme3.bullet.animation.IKController
-
Test whether this controller is enabled.
- isEnabled() - Method in class com.jme3.bullet.control.AbstractPhysicsControl
-
Test whether this Control is enabled.
- isEnabled() - Method in class com.jme3.bullet.control.GhostControl
-
Test whether this Control is enabled.
- isEnabled() - Method in interface com.jme3.bullet.control.PhysicsControl
-
Test whether this control is enabled.
- isEnabled() - Method in class com.jme3.bullet.control.RigidBodyControl
-
Test whether this Control is enabled.
- isEnabled() - Method in class com.jme3.bullet.control.VehicleControl
-
Test whether this Control is enabled.
- isEnabled() - Method in class com.jme3.bullet.debug.DebugConfiguration
-
Test whether (debug) visualization is enabled.
- isEnabled() - Method in class com.jme3.bullet.joints.Anchor
-
Test whether this Anchor is enabled.
- isEnabled() - Method in class com.jme3.bullet.joints.Constraint
-
Test whether this Constraint is enabled.
- isEnabled() - Method in class com.jme3.bullet.joints.PhysicsJoint
-
Test whether this joint is enabled.
- isEnabled() - Method in class com.jme3.bullet.joints.SoftPhysicsJoint
-
Test whether this joint is enabled.
- isEnabled(int) - Method in class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
Test whether the indexed axis is enabled (native field: m_enableMotor).
- isEnabled(Control) - Static method in class jme3utilities.minie.MyControlP
-
Test whether a scene-graph control is enabled.
- isEnabled(DumpFlags) - Method in class jme3utilities.minie.PhysicsDumper
-
Test whether the specified dump flag is set.
- isEnableMotor() - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Test whether this motor is enabled (native field: m_enableMotor).
- isFeedback() - Method in class com.jme3.bullet.joints.Constraint
-
Test whether this Constraint has feedback enabled.
- isFindBestPlane() - Method in class vhacd4.Vhacd4Parameters
-
Test whether V-HACD should try to find the optimal location for splitting hulls (native field: m_findBestPlane).
- isForceUpdateAllAabbs() - Method in class com.jme3.bullet.CollisionSpace
-
Test whether the bounding boxes of inactive collision objects should be recomputed during each
update()
(native field: m_forceUpdateAllAabbs). - isFrontWheel() - Method in class com.jme3.bullet.objects.VehicleWheel
-
Test whether this wheel is a front (steering) wheel (native field: m_bIsFrontWheel).
- isGravityProtected() - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Test whether the body's gravity can be overwritten by PhysicsSpace.
- isInfinite() - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Test whether the shape's type is infinite.
- isInsideTriangle(Vector3f, float, Vector3f, Vector3f, Vector3f) - Static method in class com.jme3.bullet.util.NativeLibrary
-
Test whether the specified point and triangle are within the specified distance of each other.
- isInWorld() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Test whether the collision object is added to a space.
- isKinematic() - Method in class com.jme3.bullet.animation.PhysicsLink
-
Test whether the link is in kinematic mode.
- isKinematic() - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Test whether the character is in kinematic mode.
- isKinematic() - Method in class com.jme3.bullet.control.JoinedBodyControl
-
Test whether the body is in kinematic mode.
- isKinematic() - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Test whether the body is in kinematic mode.
- isKinematicSpatial() - Method in class com.jme3.bullet.control.RigidBodyControl
-
Test whether this Control is in kinematic mode.
- isLateralFrictionInitialized() - Method in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Test whether the contact point's lateral friction is initialized.
- isLeafNode(int) - Method in class com.jme3.bullet.collision.shapes.infos.BoundingValueHierarchy
-
Test whether the specified node is a leaf.
- isMotorEnabled() - Method in class com.jme3.bullet.joints.motors.RotationMotor
-
Test whether the motor is enabled (native field: m_enableMotor).
- isMotorEnabled(int) - Method in class com.jme3.bullet.joints.motors.TranslationMotor
-
Test whether the indexed motor is enabled (m_enableMotor).
- isMotorEnabled(int) - Method in class com.jme3.bullet.joints.New6Dof
-
Test whether the motor is enabled for the indexed degree of freedom.
- isNonMoving() - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Test whether the shape can be applied to a dynamic rigid body.
- isOnGround() - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Test whether the character is supported by another collision object.
- isPhysical(Spatial) - Static method in class jme3utilities.minie.MyControlP
-
Test whether a Spatial is physics-controlled.
- isPolyhedral() - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Test whether this shape is convex and defined by polygons.
- isPoweredAngMotor() - Method in class com.jme3.bullet.joints.SliderJoint
-
Test whether the rotation motor is powered.
- isPoweredLinMotor() - Method in class com.jme3.bullet.joints.SliderJoint
-
Test whether the translation motor is powered.
- isQuickprof() - Static method in class com.jme3.bullet.util.NativeLibrary
-
Test whether the native library includes Quickprof profiling.
- isReady() - Method in class com.jme3.bullet.animation.DacLinks
-
Test whether this control is ready for dynamic mode.
- isReleased() - Method in class com.jme3.bullet.animation.AttachmentLink
-
Test whether the attached model has been released.
- isReleased() - Method in class com.jme3.bullet.animation.PhysicsLink
-
Test whether the attached model (if any) has been released.
- isRunning() - Method in class com.jme3.bullet.BulletAppState
-
Test whether the physics simulation is running (started but not yet stopped).
- isSerializingBvh() - Static method in class com.jme3.bullet.collision.shapes.MeshCollisionShape
-
Test whether bounding-value hierarchies will be serialized when serializing mesh collision shapes.
- isServoEnabled() - Method in class com.jme3.bullet.joints.motors.RotationMotor
-
Test whether the servo is enabled (native field: m_servoMotor).
- isServoEnabled(int) - Method in class com.jme3.bullet.joints.motors.TranslationMotor
-
Test whether the indexed servo is enabled (m_servoMotor).
- isServoEnabled(int) - Method in class com.jme3.bullet.joints.New6Dof
-
Test whether the servo is enabled for the indexed degree of freedom.
- isShrinkWrap() - Method in class vhacd4.Vhacd4Parameters
-
Test whether V-HACD should shrinkwrap voxel positions to the source mesh (native field: m_shrinkWrap).
- isSoftRigid() - Method in class com.jme3.bullet.joints.SoftPhysicsJoint
-
Test whether this joint is a soft-rigid joint.
- isSoftSoft() - Method in class com.jme3.bullet.joints.SoftPhysicsJoint
-
Test whether this joint is a soft-soft joint.
- isSplitImpulseEnabled() - Method in class com.jme3.bullet.SolverInfo
-
Test whether split impulse is enabled globally (native field: m_splitImpulse).
- isSpringEnabled() - Method in class com.jme3.bullet.joints.motors.RotationMotor
-
Test whether the spring is enabled (native field: m_enableSpring).
- isSpringEnabled(int) - Method in class com.jme3.bullet.joints.motors.TranslationMotor
-
Test whether the indexed spring is enabled (m_enableSpring).
- isSpringEnabled(int) - Method in class com.jme3.bullet.joints.New6Dof
-
Test whether the spring is enabled for the indexed degree of freedom.
- isSpringEnabled(int) - Method in class com.jme3.bullet.joints.SixDofSpringJoint
-
Test whether the spring for the indexed degree of freedom is enabled.
- isStatic() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Test whether the collision object is static (immobile).
- isStiffnessLimited() - Method in class com.jme3.bullet.joints.motors.RotationMotor
-
Test whether the spring's stiffness is limited (m_springStiffnessLimited).
- isStiffnessLimited(int) - Method in class com.jme3.bullet.joints.motors.TranslationMotor
-
Test whether the indexed spring's stiffness is limited (m_springStiffnessLimited).
- isThreadSafe() - Static method in class com.jme3.bullet.util.NativeLibrary
-
Test whether the native library was built thread-safe.
- isUsingDeterministicDispatch() - Method in class com.jme3.bullet.CollisionSpace
-
Test whether the "deterministic overlapping pairs" option is enabled in the collision dispatcher (native field: m_deterministicOverlappingPairs).
- isUsingGhostSweepTest() - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Test whether the ghost's convex-sweep test is in use.
- isUsingGhostSweepTest() - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Test whether the ghost's convex-sweep test is in use.
- isUsingGlobalVelocities() - Method in class com.jme3.bullet.MultiBody
-
Test whether this MultiBody uses global variables.
- isUsingGyroTerm() - Method in class com.jme3.bullet.MultiBody
-
Test whether this MultiBody uses the gyro term.
- isUsingRK4() - Method in class com.jme3.bullet.MultiBody
-
Test whether this MultiBody uses RK4 integration.
- isUsingScr() - Method in class com.jme3.bullet.PhysicsSpace
-
Test whether the space uses Speculative Contact Restitution (native field: m_applySpeculativeContactRestitution).
- isWorldInfoProtected() - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Test whether this body's world info should be replaced when added to a space.
J
- jme3utilities.minie - package jme3utilities.minie
-
Bullet physics support for jMonkeyEngine3.
- jmeClone() - Method in class com.jme3.bullet.animation.IKController
-
Create a shallow clone for the JME cloner.
- jmeClone() - Method in class com.jme3.bullet.animation.IKJoint
-
Create a shallow clone for the JME cloner.
- jmeClone() - Method in class com.jme3.bullet.animation.PhysicsLink
-
Create a shallow clone for the JME cloner.
- jmeClone() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Create a shallow clone for the JME cloner.
- jmeClone() - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Create a shallow clone for the JME cloner.
- jmeClone() - Method in class com.jme3.bullet.collision.shapes.infos.BoundingValueHierarchy
-
Create a shallow clone for the JME cloner.
- jmeClone() - Method in class com.jme3.bullet.collision.shapes.infos.ChildCollisionShape
-
Create a shallow clone for the JME cloner.
- jmeClone() - Method in class com.jme3.bullet.collision.shapes.infos.CompoundMesh
-
Create a shallow clone for the JME cloner.
- jmeClone() - Method in class com.jme3.bullet.collision.shapes.infos.IndexedMesh
-
Create a shallow clone for the JME cloner.
- jmeClone() - Method in class com.jme3.bullet.control.AbstractPhysicsControl
-
Create a shallow clone for the JME cloner.
- jmeClone() - Method in class com.jme3.bullet.debug.AbstractPhysicsDebugControl
-
Create a shallow clone for the JME cloner.
- jmeClone() - Method in class com.jme3.bullet.joints.PhysicsJoint
-
Create a shallow clone for the JME cloner.
- jmeClone() - Method in class com.jme3.bullet.MultiBody
-
Create a shallow clone for the JME cloner.
- jmeClone() - Method in class com.jme3.bullet.MultiBodyLink
-
Create a shallow clone for the JME cloner.
- jmeClone() - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Create a shallow clone for the JME cloner.
- jmeClone() - Method in class com.jme3.bullet.objects.infos.RigidBodyMotionState
-
Create a shallow clone for the JME cloner.
- jmeClone() - Method in class com.jme3.bullet.objects.infos.SoftBodyConfig
-
Create a shallow clone for the JME cloner.
- jmeClone() - Method in class com.jme3.bullet.objects.infos.SoftBodyMaterial
-
Create a shallow clone for the JME cloner.
- jmeClone() - Method in class com.jme3.bullet.objects.infos.VehicleTuning
-
Create a shallow clone for the JME cloner.
- jmeClone() - Method in class com.jme3.bullet.objects.VehicleWheel
-
Create a shallow clone for the JME cloner.
- jmeClone() - Method in class com.jme3.bullet.SoftBodyWorldInfo
-
Create a shallow clone for the JME cloner.
- jniEnvId() - Method in class com.jme3.bullet.CollisionSpace
-
Return the address of the JNIEnv that the space uses for callbacks.
- jniEnvId() - Static method in class com.jme3.bullet.util.NativeLibrary
-
Return the address of the current thread's JNIEnv.
- JoinedBodyControl - Class in com.jme3.bullet.control
-
A custom PhysicsControl for a dynamic rigid body that can be joined to other bodies.
- JoinedBodyControl() - Constructor for class com.jme3.bullet.control.JoinedBodyControl
-
No-argument constructor needed by SavableClassUtil.
- JoinedBodyControl(CollisionShape, float) - Constructor for class com.jme3.bullet.control.JoinedBodyControl
-
Instantiate an enabled Control in dynamic mode.
- Joint - Enum constant in enum class com.jme3.bullet.animation.CenterHeuristic
-
for bone links only: center on the joint's pivot
- JointEnd - Enum Class in com.jme3.bullet.joints
-
Enumerate the ends of a physics joint.
- jointErp() - Method in class com.jme3.bullet.SolverInfo
-
Return the error-reduction parameter for non-contact constraints (native field: m_erp).
- jointPosition(int) - Method in class com.jme3.bullet.MultiBodyLink
-
Determine the position of the indexed DOF.
- JointsInBodies - Enum constant in enum class jme3utilities.minie.DumpFlags
-
physics joints in rigid bodies
- JointsInSpaces - Enum constant in enum class jme3utilities.minie.DumpFlags
-
joints in physics spaces
- jointTorque(int) - Method in class com.jme3.bullet.MultiBodyLink
-
Determine the torque applied to the indexed DOF using
MultiBodyLink.addJointTorque(int, float)
, which is zeroed after each simulation step. - jointType() - Method in class com.jme3.bullet.MultiBodyLink
-
Determine the type of joint between this link and its parent.
- jointVelocity(int) - Method in class com.jme3.bullet.MultiBodyLink
-
Determine the velocity of the indexed DOF.
- jump() - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Apply a jump impulse during the next simulation step if the character is on ground and not in kinematic mode.
- jump() - Method in class com.jme3.bullet.control.CharacterControl
-
Jump in the "up" direction.
- jump() - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Jump in the "up" direction.
- jump(Vector3f) - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Jump in the specified direction.
- jump(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Jump in the specified direction.
K
- KeepUnflippedNormal - Static variable in class com.jme3.bullet.RayTestFlag
-
when a ray hits a back-facing triangle, don't reverse the face normal (native value: kF_KeepUnflippedNormal)
- KINEMATIC_OBJECT - Static variable in class com.jme3.bullet.collision.CollisionFlag
-
flag for a kinematic object
- KinematicSubmode - Enum Class in com.jme3.bullet.animation
-
Enumerate submodes for a link in kinematic mode.
- kinematicUpdate(float) - Method in class com.jme3.bullet.animation.AttachmentLink
-
Update this link in blended Kinematic mode.
- kinematicUpdate(float) - Method in class com.jme3.bullet.animation.BoneLink
-
Update this link in blended Kinematic mode.
- kinematicUpdate(float) - Method in class com.jme3.bullet.animation.PhysicsLink
-
Update this link in blended Kinematic mode.
- kinematicUpdate(float) - Method in class com.jme3.bullet.animation.TorsoLink
-
Update this link in blended Kinematic mode.
- kinematicWeight() - Method in class com.jme3.bullet.animation.PhysicsLink
-
Read the kinematic weight of this link.
- kineticEnergy() - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Calculate the ragdoll's total kinetic energy, excluding released attachments.
- kineticEnergy() - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Calculate the body's kinetic energy (linear + angular).
- KineticHardness - Enum constant in enum class com.jme3.bullet.objects.infos.Sbcp
-
contact hardness coefficient for static or kinematic rigid bodies (≥0, ≤1, default=0.1, native field: kKHR)
L
- lastValue - Static variable in class com.jme3.bullet.collision.Activation
-
highest legal value, for range checks
- LATERAL_FRICTION - Static variable in class com.jme3.bullet.collision.ContactPointFlag
-
lateral friction is initialized
- Lemke - Enum constant in enum class com.jme3.bullet.SolverType
-
btLemkeSolver: accurate-but-slow MLCP direct solver using Lemke’s Algorithm (see "Fast Implementation of Lemke’s Algorithm for Rigid Body Contact Simulation" by John E.
- Lift - Enum constant in enum class com.jme3.bullet.objects.infos.Sbcp
-
lift coefficient (≥0, default=0, native field: kLF)
- linearDamping() - Method in class com.jme3.bullet.MultiBody
-
Determine the linear damping.
- LinearDamping - Enum constant in enum class com.jme3.bullet.objects.infos.Cluster
-
linear damping coefficient (default=0, native field: m_ldamping)
- linearStiffness() - Method in class com.jme3.bullet.objects.infos.SoftBodyMaterial
-
Read the linear-stiffness coefficient (native field: m_kLST).
- link(String, float, RangeOfMotion) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Link the named bone using the specified mass and range of motion.
- link(String, LinkConfig, RangeOfMotion) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Link the named bone using the specified configuration and range of motion.
- LinkConfig - Class in com.jme3.bullet.animation
-
Configuration data for a PhysicsLink, not including the bone name, attached model, or RangeOfMotion.
- LinkConfig() - Constructor for class com.jme3.bullet.animation.LinkConfig
-
Instantiate a configuration for a link with mass=1, centered on the unweighted average of the vertex locations, shaped to the convex hull of the vertices.
- LinkConfig(float) - Constructor for class com.jme3.bullet.animation.LinkConfig
-
Instantiate a configuration for a link with the specified mass, centered on the unweighted average of the vertex locations, shaped to the convex hull of the vertices.
- LinkConfig(float, LinkConfig) - Constructor for class com.jme3.bullet.animation.LinkConfig
-
Instantiate a configuration for a link with the specified mass, but with the centering and shaping of the specified configuration.
- LinkConfig(float, MassHeuristic, ShapeHeuristic, Vector3f, CenterHeuristic) - Constructor for class com.jme3.bullet.animation.LinkConfig
-
Instantiate a custom configuration with no RotationOrder.
- LinkConfig(float, MassHeuristic, ShapeHeuristic, Vector3f, CenterHeuristic, RotationOrder) - Constructor for class com.jme3.bullet.animation.LinkConfig
-
Instantiate a custom configuration with a RotationOrder.
- linkIndex() - Method in class com.jme3.bullet.objects.MultiBodyCollider
-
Determine the index of the corresponding MultiBodyLink.
- LinksOnly - Enum constant in enum class com.jme3.bullet.control.UseTriangles
-
use triangle indices to generate soft-body links only
- listAttachmentBoneNames() - Method in class com.jme3.bullet.animation.DacConfiguration
-
Enumerate bones with attachment links.
- listAttachmentLinks() - Method in class com.jme3.bullet.animation.DacLinks
-
Enumerate attachment links.
- listChildren() - Method in class com.jme3.bullet.animation.PhysicsLink
-
Enumerate this link's immediate children in the link hierarchy.
- listChildren() - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Enumerate the child shapes.
- listColliders() - Method in class com.jme3.bullet.MultiBody
-
Enumerate the colliders in this MultiBody.
- listDacMeshes(Spatial, List<Mesh>) - Static method in class com.jme3.bullet.animation.RagUtils
-
Enumerate all animated meshes in the specified subtree of a scene graph, skipping spatials tagged with "JmePhysicsIgnore".
- listExceptions() - Method in class jme3utilities.minie.FilterAll
-
Enumerate the exceptions.
- listIgnoredPcos() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Enumerate all collision objects in this object's ignore list.
- listIKControllers() - Method in class com.jme3.bullet.animation.PhysicsLink
-
Enumerate inverse-kinematics controllers for this link.
- listIKJoints() - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Enumerate IK joints managed by this Control.
- listInternalJoints(PhysicsBody...) - Static method in class com.jme3.bullet.animation.RagUtils
-
Enumerate all physics joints that connect bodies in the specified array.
- listJoints() - Method in class com.jme3.bullet.objects.PhysicsBody
-
Enumerate the joints connected to this body.
- listLinkedBoneNames() - Method in class com.jme3.bullet.animation.DacConfiguration
-
Enumerate bones with bone links.
- listLinks(Class<T>) - Method in class com.jme3.bullet.animation.DacLinks
-
Enumerate physics links of the specified type managed by this control.
- listManifoldIds() - Method in class com.jme3.bullet.PhysicsSpace
-
Enumerate the native IDs of all collision manifolds in the space.
- listNodesInCluster(int, IntBuffer) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
List all nodes in the indexed cluster.
- listPointIds(long) - Static method in class com.jme3.bullet.collision.PersistentManifolds
-
Enumerate the native IDs of all points in the specified manifold.
- listRigidBodies() - Method in class com.jme3.bullet.animation.DacLinks
-
Enumerate all rigid bodies managed by this control.
- listVolumes(CompoundCollisionShape) - Static method in class jme3utilities.minie.MyShape
-
Estimate the volume of each child in a CompoundCollisionShape.
- localOffset(Vector3f) - Method in class com.jme3.bullet.animation.PhysicsLink
-
Copy the local offset of this link.
- locateSupport(float, float, float) - Method in class com.jme3.bullet.collision.shapes.CustomConvexShape
-
Locate the shape's supporting vertex for the specified normal direction, excluding collision margin.
- location(Vector3f) - Method in class com.jme3.bullet.MultiBodyLink
-
Determine the location of this link's center of mass.
- logger - Static variable in class com.jme3.bullet.animation.IKController
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.animation.IKJoint
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.animation.LinkConfig
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.animation.PhysicsLink
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.animation.PreComposer
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.animation.RangeOfMotion
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.BulletAppState
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.collision.Activation
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.collision.AfMode
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.collision.CollisionFlag
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.collision.ContactPointFlag
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.collision.ManifoldPoints
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.collision.PcoType
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.collision.PersistentManifolds
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.collision.PhysicsCollisionEvent
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.collision.PhysicsCollisionObject
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.collision.PhysicsRayTestResult
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.collision.PhysicsSweepTestResult
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.collision.shapes.CollisionShape
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.collision.shapes.infos.BoundingValueHierarchy
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.collision.shapes.infos.ChildCollisionShape
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.collision.shapes.infos.CompoundMesh
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.collision.shapes.infos.IndexedMesh
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.CollisionConfiguration
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.control.AbstractPhysicsControl
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.debug.BulletCharacterDebugControl
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.debug.BulletDebugAppState
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.debug.BulletGhostObjectDebugControl
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.debug.BulletRigidBodyDebugControl
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.debug.BulletVehicleDebugControl
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.debug.DebugConfiguration
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.debug.DebugTools
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.joints.motors.RotationMotor
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.joints.motors.TranslationMotor
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.joints.PhysicsJoint
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.MultiBody
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.MultiBodyLink
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.objects.infos.CharacterController
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.objects.infos.ConfigFlag
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.objects.infos.RigidBodyMotionState
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.objects.infos.RigidBodySnapshot
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.objects.infos.SoftBodyConfig
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.objects.infos.SoftBodyMaterial
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.objects.infos.VehicleController
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.objects.infos.VehicleTuning
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.objects.VehicleWheel
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.PhysicsSpace
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.RayTestFlag
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.SoftBodyWorldInfo
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.SolverInfo
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.SolverMode
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.util.CollisionShapeFactory
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.util.DebugShapeFactory
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.util.NativeLibrary
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.util.NativeSoftBodyUtil
-
message logger for this class
- logger - Static variable in class com.jme3.bullet.util.PlaneDmiListener
-
message logger for this class
- logger - Static variable in class jme3utilities.minie.FilterAll
-
message logger for this class
- logger - Static variable in class jme3utilities.minie.MinieVersion
-
message logger for this class
- logger - Static variable in class jme3utilities.minie.MyControlP
-
message logger for this class
- logger - Static variable in class jme3utilities.minie.MyPco
-
message logger for this class
- logger - Static variable in class jme3utilities.minie.MyShape
-
message logger for this class
- logger - Static variable in class jme3utilities.minie.PhysicsDescriber
-
message logger for this class
- logger - Static variable in class jme3utilities.minie.PhysicsDumper
-
message logger for this class
- logger - Static variable in class vhacd.VHACD
-
message logger for this class
- logger - Static variable in class vhacd.VHACDHull
-
message logger for this class
- logger - Static variable in class vhacd.VHACDParameters
-
message logger for this class
- logger - Static variable in class vhacd4.Vhacd4
-
message logger for this class
- logger - Static variable in class vhacd4.Vhacd4Hull
-
message logger for this class
- logger - Static variable in class vhacd4.Vhacd4Parameters
-
message logger for this class
- logger15 - Static variable in class com.jme3.bullet.joints.Constraint
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.animation.AttachmentLink
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.animation.BoneLink
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.animation.DacConfiguration
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.animation.TorsoLink
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.collision.shapes.Box2dShape
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.collision.shapes.BoxCollisionShape
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.collision.shapes.CapsuleCollisionShape
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.collision.shapes.ConeCollisionShape
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.collision.shapes.ConicalFrustum
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.collision.shapes.Convex2dShape
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.collision.shapes.CylinderCollisionShape
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.collision.shapes.EmptyShape
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.collision.shapes.GImpactCollisionShape
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.collision.shapes.HeightfieldCollisionShape
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.collision.shapes.HullCollisionShape
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.collision.shapes.MeshCollisionShape
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.collision.shapes.MinkowskiSum
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.collision.shapes.MultiSphere
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.collision.shapes.PlaneCollisionShape
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.collision.shapes.SimplexCollisionShape
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.collision.shapes.SphereCollisionShape
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.collision.shapes.SphericalSegment
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.control.BetterCharacterControl
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.control.CharacterControl
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.control.SoftBodyControl
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.debug.MultiBodyDebugAppState
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.debug.SoftDebugAppState
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.joints.Anchor
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.joints.ConeJoint
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.joints.GearJoint
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.joints.HingeJoint
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.joints.New6Dof
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.joints.Point2PointJoint
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.joints.SixDofJoint
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.joints.SliderJoint
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.joints.SoftPhysicsJoint
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.MultiBodyAppState
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.MultiBodySpace
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.objects.MultiBodyCollider
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.objects.PhysicsCharacter
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.objects.PhysicsGhostObject
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.objects.PhysicsRigidBody
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.objects.PhysicsSoftBody
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.PhysicsSoftSpace
-
message logger for this class
- logger2 - Static variable in class com.jme3.bullet.SoftPhysicsAppState
-
message logger for this class
- logger3 - Static variable in class com.jme3.bullet.animation.DacLinks
-
message logger for this class
- logger3 - Static variable in class com.jme3.bullet.control.GhostControl
-
message logger for this class
- logger3 - Static variable in class com.jme3.bullet.control.JoinedBodyControl
-
message logger for this class
- logger3 - Static variable in class com.jme3.bullet.control.RigidBodyControl
-
message logger for this class
- logger3 - Static variable in class com.jme3.bullet.DeformableSpace
-
message logger for this class
- logger3 - Static variable in class com.jme3.bullet.joints.NewHinge
-
message logger for this class
- logger3 - Static variable in class com.jme3.bullet.joints.SixDofSpringJoint
-
message logger for this class
- logger3 - Static variable in class com.jme3.bullet.joints.SoftAngularJoint
-
message logger for this class
- logger3 - Static variable in class com.jme3.bullet.joints.SoftLinearJoint
-
message logger for this class
- logger3 - Static variable in class com.jme3.bullet.objects.PhysicsVehicle
-
message logger for this class
- logger35 - Static variable in class com.jme3.bullet.animation.DynamicAnimControl
-
message logger for this class
- logger4 - Static variable in class com.jme3.bullet.control.VehicleControl
-
message logger for this class
- loggerC - Static variable in class com.jme3.bullet.CollisionSpace
-
message logger for this class
- loggerN - Static variable in class com.jme3.bullet.NativePhysicsObject
-
message logger for this class
- loggerX - Static variable in class com.jme3.bullet.collision.shapes.ConvexShape
-
message logger for this class
- loggerY - Static variable in class com.jme3.bullet.collision.shapes.CustomConvexShape
-
message logger for this class
- LowerLimit - Enum constant in enum class com.jme3.bullet.joints.motors.MotorParam
-
constraint lower limit (m_loLimit/m_lowerLimit, default=1[rot] or 0[translate])
- lowResolution - Static variable in class com.jme3.bullet.util.DebugShapeFactory
-
specify low-res debug meshes for convex shapes (up to 42 vertices) and zero-margin debug meshes for concave shapes
M
- mainAxisIndex(CollisionShape) - Static method in class jme3utilities.minie.MyShape
-
Determine the main axis of the specified shape, provided it's a capsule, cone, or cylinder.
- mainBoneName() - Method in class com.jme3.bullet.animation.DacConfiguration
-
Return the name of the main bone.
- makeCylinder(VectorSet, Vector3f) - Static method in class com.jme3.bullet.animation.RagUtils
-
Create a transformed CylinderCollisionShape that bounds the locations in the specified VectorSet.
- makeRectangularSolid(VectorSet, Vector3f) - Static method in class com.jme3.bullet.animation.RagUtils
-
Instantiate a compact RectangularSolid that bounds the sample locations contained in a VectorSet.
- manager - Variable in class com.jme3.bullet.debug.DebugTools
-
asset manager
- managerMap(Armature) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Create a map from joint indices to the names of the armature joints that manage them.
- managerMap(Skeleton) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Create a map from bone indices to the names of the bones that manage them.
- ManifoldPoints - Class in com.jme3.bullet.collision
-
Utility class to access fields of Bullet's
btManifoldPoint
class. - mapIndices(IntBuffer, IndexBuffer, IndexBuffer) - Static method in class com.jme3.bullet.util.NativeSoftBodyUtil
-
Map all indices in the specified input buffer using the specified map buffer.
- mapVertexData(IntBuffer, FloatBuffer, int) - Static method in class com.jme3.bullet.util.NativeSoftBodyUtil
-
Copy all vertex data in the specified input buffer, using the specified map buffer to map vertex indices.
- margin - Variable in class com.jme3.bullet.collision.shapes.CollisionShape
-
copy of collision margin (in physics-space units, >0, default=0.04)
- margin() - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Read the collision margin of this body.
- mass - Variable in class com.jme3.bullet.objects.PhysicsRigidBody
-
JVM copy of the mass (>0) of a dynamic body, or 0 for a static body
- mass() - Method in class com.jme3.bullet.animation.LinkConfig
-
Calculate the mass, if it can be determined from the configuration alone.
- mass() - Method in class com.jme3.bullet.MultiBodyLink
-
Determine the mass of this link.
- mass() - Method in class com.jme3.bullet.objects.MultiBodyCollider
-
Determine the mass of this collider.
- mass(Spatial) - Static method in class jme3utilities.minie.MyControlP
-
Return the mass of the specified
Spatial
. - mass(String) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Return the mass of the named bone/torso.
- mass(String) - Method in class com.jme3.bullet.animation.DacLinks
-
Return the mass of the named bone/torso.
- Mass - Enum constant in enum class com.jme3.bullet.animation.MassHeuristic
-
use the configured parameter directly
- massForStatic - Static variable in class com.jme3.bullet.objects.PhysicsBody
-
magic mass value used to specify a static rigid body or soft-body node
- massHeuristic() - Method in class com.jme3.bullet.animation.LinkConfig
-
Read which mass heuristic to use.
- MassHeuristic - Enum Class in com.jme3.bullet.animation
-
Enumerate algorithms to determine the mass for a PhysicsLink.
- massParameter() - Method in class com.jme3.bullet.animation.LinkConfig
-
Read the parameter used to determine the mass.
- Matching - Enum constant in enum class com.jme3.bullet.objects.infos.Cluster
-
matching coefficient (default=0, native field: m_matching)
- MatParams - Enum constant in enum class jme3utilities.minie.DumpFlags
-
parameters in materials
- matrixToEuler(Matrix3f, Vector3f) - Method in enum class com.jme3.bullet.RotationOrder
-
Convert a rotation matrix to Euler angles for this RotationOrder.
- maxAppliedImpulse() - Method in class com.jme3.bullet.MultiBody
-
Determine the maximum applied impulse.
- maxCoordinateVelocity() - Method in class com.jme3.bullet.MultiBody
-
Determine the maximum coordinate velocity.
- maxDisplacement() - Method in class com.jme3.bullet.SoftBodyWorldInfo
-
Return the maximum distance a node can travel in a simulation step.
- maxDistance(CollisionShape, Transform, int) - Static method in class com.jme3.bullet.util.DebugShapeFactory
-
Estimate how far the specified (non-compound, non-plane) shape extends from some origin, based on its debug mesh.
- maxDistance(Transform) - Method in class com.jme3.bullet.collision.shapes.infos.IndexedMesh
-
Calculate how far the mesh extends from some origin.
- maxManifolds() - Method in class com.jme3.bullet.CollisionConfiguration
-
Return the size of the persistent-manifold pool.
- maxMin(Vector3f, Vector3f) - Method in class com.jme3.bullet.collision.shapes.infos.CompoundMesh
-
Find the maximum and minimum coordinates for each local axis among the scaled vertices in this mesh.
- maxMin(Vector3f, Vector3f) - Method in class com.jme3.bullet.collision.shapes.infos.IndexedMesh
-
Find the maximum and minimum coordinates for each axis among the vertices in this mesh.
- MaxMotorForce - Enum constant in enum class com.jme3.bullet.joints.motors.MotorParam
-
maximum motor force (m_maxMotorForce, default=6[rot] or 0[translate])
- maxRadius() - Method in class com.jme3.bullet.collision.shapes.Box2dShape
-
Calculate how far the scaled shape extends from its center.
- maxRadius() - Method in class com.jme3.bullet.collision.shapes.BoxCollisionShape
-
Calculate how far the scaled shape extends from its center.
- maxRadius() - Method in class com.jme3.bullet.collision.shapes.CapsuleCollisionShape
-
Calculate how far the scaled shape extends from its center.
- maxRadius() - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Estimate how far the scaled shape extends from its center, including margin.
- maxRadius() - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Estimate how far the shape extends from its origin.
- maxRadius() - Method in class com.jme3.bullet.collision.shapes.ConeCollisionShape
-
Calculate how far the scaled shape extends from its center of mass, including collision margin.
- maxRadius() - Method in class com.jme3.bullet.collision.shapes.ConicalFrustum
-
Calculate how far the scaled shape extends from its center of mass, including collision margin.
- maxRadius() - Method in class com.jme3.bullet.collision.shapes.CylinderCollisionShape
-
Calculate how far the scaled shape extends from its center.
- maxRadius() - Method in class com.jme3.bullet.collision.shapes.EmptyShape
-
Calculate how far the shape extends from its center.
- maxRadius() - Method in class com.jme3.bullet.collision.shapes.HullCollisionShape
-
Calculate how far this shape extends from its center, including margin.
- maxRadius() - Method in class com.jme3.bullet.collision.shapes.PlaneCollisionShape
-
Calculate how far the shape extends.
- maxRadius() - Method in class com.jme3.bullet.collision.shapes.SimplexCollisionShape
-
Calculate how far the shape extends from its origin, including margin.
- maxRadius() - Method in class com.jme3.bullet.collision.shapes.SphereCollisionShape
-
Calculate how far the scaled shape extends from its center.
- maxRadius() - Method in class com.jme3.bullet.collision.shapes.SphericalSegment
-
Calculate how far the scaled shape extends from its center of mass, including collision margin.
- MaxSelfImpulse - Enum constant in enum class com.jme3.bullet.objects.infos.Cluster
-
maximum self-collision impulse (default=100, native field: m_maxSelfCollisionImpulse)
- maxSubmeshes - Static variable in class com.jme3.bullet.collision.shapes.MeshCollisionShape
-
maximum number of submeshes when compression is used
- maxSubSteps() - Method in class com.jme3.bullet.PhysicsSpace
-
Return the maximum number of simulation steps per frame.
- maxTimeStep() - Method in class com.jme3.bullet.PhysicsSpace
-
Return the maximum time step (imposed when maxSubSteps=0).
- maxTrianglesInAnySubmesh - Static variable in class com.jme3.bullet.collision.shapes.MeshCollisionShape
-
maximum number of triangles in any submesh when compression is used
- maxValue() - Method in enum class com.jme3.bullet.joints.motors.MotorParam
-
Determine the maximum value for this parameter.
- maxValue() - Method in enum class com.jme3.bullet.objects.infos.Cluster
-
Determine the maximum value for this parameter.
- maxValue() - Method in enum class com.jme3.bullet.objects.infos.Sbcp
-
Determine the maximum value for this parameter.
- MaxVolumeRatio - Enum constant in enum class com.jme3.bullet.objects.infos.Sbcp
-
maximum volume ratio for the pose (default=1, native field: maxvolume)
- Mean - Enum constant in enum class com.jme3.bullet.animation.CenterHeuristic
-
unweighted average of vertex locations
- mechanicalEnergy() - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Calculate the ragdoll's total mechanical energy, excluding released attachments.
- mechanicalEnergy() - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Calculate the mechanical energy of the body (kinetic + potential) assuming a uniform gravitational field.
- MeshCollisionShape - Class in com.jme3.bullet.collision.shapes
-
A mesh collision shape that uses a Bounding Value Hierarchy (BVH), based on Bullet's
btBvhTriangleMeshShape
. - MeshCollisionShape() - Constructor for class com.jme3.bullet.collision.shapes.MeshCollisionShape
-
No-argument constructor needed by SavableClassUtil.
- MeshCollisionShape(boolean, CompoundMesh) - Constructor for class com.jme3.bullet.collision.shapes.MeshCollisionShape
-
Instantiate a shape based on the specified CompoundMesh.
- MeshCollisionShape(boolean, IndexedMesh...) - Constructor for class com.jme3.bullet.collision.shapes.MeshCollisionShape
-
Instantiate a shape from the specified native mesh(es).
- MeshCollisionShape(boolean, Collection<IndexedMesh>) - Constructor for class com.jme3.bullet.collision.shapes.MeshCollisionShape
-
Instantiate a shape from the specified collection of native meshes.
- MeshCollisionShape(byte[], IndexedMesh...) - Constructor for class com.jme3.bullet.collision.shapes.MeshCollisionShape
-
Instantiate a shape from the specified native mesh(es) and serialized BVH.
- MeshCollisionShape(Mesh...) - Constructor for class com.jme3.bullet.collision.shapes.MeshCollisionShape
-
Instantiate a shape based on the specified JME mesh(es), using quantized AABB compression.
- MeshCollisionShape(Mesh, boolean) - Constructor for class com.jme3.bullet.collision.shapes.MeshCollisionShape
-
Instantiate a shape based on the specified JME mesh.
- MeshCustomizer - Interface in com.jme3.bullet.debug
-
Interface used to customize debug meshes.
- meshToLocal(Bone, Transform) - Static method in class com.jme3.bullet.animation.RagUtils
-
Convert a transform from the mesh coordinate system to the local coordinate system of the specified bone.
- minBatch() - Method in class com.jme3.bullet.SolverInfo
-
Determine the minimum batch size (native field: m_minimumSolverBatchSize).
- MinBox - Enum constant in enum class com.jme3.bullet.animation.ShapeHeuristic
-
minimal bounding box (not axis-aligned)
- MinieVersion - Class in jme3utilities.minie
-
Version strings for the Minie library.
- MinkowskiSum - Class in com.jme3.bullet.collision.shapes
-
A convex collision shape to represent the Minkowki sum of 2 convex shapes, based on Bullet's
btMinkowskiSumShape
. - MinkowskiSum() - Constructor for class com.jme3.bullet.collision.shapes.MinkowskiSum
-
No-argument constructor needed by SavableClassUtil.
- MinkowskiSum(ConvexShape, ConvexShape) - Constructor for class com.jme3.bullet.collision.shapes.MinkowskiSum
-
Instantiate the Minkowki sum of the specified shapes.
- minValue() - Method in enum class com.jme3.bullet.joints.motors.MotorParam
-
Determine the minimum value for this parameter.
- minValue() - Method in enum class com.jme3.bullet.objects.infos.Cluster
-
Determine the minimum value for this parameter.
- minValue() - Method in enum class com.jme3.bullet.objects.infos.Sbcp
-
Determine the minimum value for this parameter.
- mode() - Method in class com.jme3.bullet.SolverInfo
-
Determine the mode flags (native field: m_solverMode).
- MotorCfm - Enum constant in enum class com.jme3.bullet.joints.motors.MotorParam
-
constraint-force mixing parameter between limits (m_motorCFM, native name: BT_CONSTRAINT_CFM, default=0)
- MotorErp - Enum constant in enum class com.jme3.bullet.joints.motors.MotorParam
-
error-reduction parameter between limits (m_motorERP, native name: BT_CONSTRAINT_ERP, default=0.9)
- MotorParam - Enum Class in com.jme3.bullet.joints.motors
-
Enumerate certain parameters of a RotationMotor or TranslationMotor, based on Bullet's btConstraintParams.
- Motors - Enum constant in enum class jme3utilities.minie.DumpFlags
-
motors in physics joints
- moveToBody(PhysicsLink, Vector3f, PhysicsRigidBody, Vector3f) - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Add an IK joint that will cause the specified link to move until its pivot location coincides with that of the specified goal body.
- moveToWorld(PhysicsLink, Vector3f, Vector3f) - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Add an IK joint that will cause the specified link to move until a fixed pivot location coincides with the specified goal location.
- MultiBody - Class in com.jme3.bullet
-
An articulated rigid body based on Bullet's
btMultiBody
. - MultiBody() - Constructor for class com.jme3.bullet.MultiBody
-
No-argument constructor needed by SavableClassUtil.
- MultiBody(int, float, Vector3f, boolean, boolean) - Constructor for class com.jme3.bullet.MultiBody
-
Instantiate a MultiBody.
- MultiBodyAppState - Class in com.jme3.bullet
-
An AppState to manage a single MultiBodySpace.
- MultiBodyAppState() - Constructor for class com.jme3.bullet.MultiBodyAppState
-
Instantiate an enabled AppState to manage a space with DBVT broadphase collision detection.
- MultiBodyCollider - Class in com.jme3.bullet.objects
-
A collision object for a link or base in a MultiBody, based on Bullet's btMultiBodyLinkCollider.
- MultiBodyCollider() - Constructor for class com.jme3.bullet.objects.MultiBodyCollider
-
No-argument constructor needed by SavableClassUtil.
- MultiBodyCollider(MultiBody, int) - Constructor for class com.jme3.bullet.objects.MultiBodyCollider
-
Instantiate a collider for the indexed link in the specified MultiBody.
- MultiBodyDebugAppState - Class in com.jme3.bullet.debug
-
An AppState to manage debug visualization of a MultiBodySpace.
- MultiBodyDebugAppState(DebugConfiguration) - Constructor for class com.jme3.bullet.debug.MultiBodyDebugAppState
-
Instantiate an AppState with the specified configuration.
- MultiBodyJointType - Enum Class in com.jme3.bullet
-
Enumerate the types of joints in a MultiBody (native name: eFeatherstoneJointType).
- MultiBodyLink - Class in com.jme3.bullet
-
A single link in a MultiBody, based on Bullet's
btMultibodyLink
. - MultiBodyLink() - Constructor for class com.jme3.bullet.MultiBodyLink
-
No-argument constructor needed by SavableClassUtil.
- MultiBodySpace - Class in com.jme3.bullet
-
A PhysicsSpace that supports multibodies, with its own
btMultiBodyDynamicsWorld
. - MultiBodySpace(Vector3f, Vector3f, PhysicsSpace.BroadphaseType) - Constructor for class com.jme3.bullet.MultiBodySpace
-
Instantiate a MultiBodySpace with a sequential-impulse solver.
- MultiBodySpace(Vector3f, Vector3f, PhysicsSpace.BroadphaseType, SolverType) - Constructor for class com.jme3.bullet.MultiBodySpace
-
Instantiate a MultiBodySpace with the specified contact-and-constraint solver.
- MultiSphere - Class in com.jme3.bullet.collision.shapes
-
A convex collision shape based on Bullet's
btMultiSphereShape
. - MultiSphere() - Constructor for class com.jme3.bullet.collision.shapes.MultiSphere
-
No-argument constructor needed by SavableClassUtil.
- MultiSphere(float) - Constructor for class com.jme3.bullet.collision.shapes.MultiSphere
-
Instantiate a centered sphere shape with the specified radius.
- MultiSphere(float, float) - Constructor for class com.jme3.bullet.collision.shapes.MultiSphere
-
Instantiate a centered Y-axis capsule shape with the specified radius and height.
- MultiSphere(float, float, int) - Constructor for class com.jme3.bullet.collision.shapes.MultiSphere
-
Instantiate a centered capsule shape with the specified radius, height, and axis.
- MultiSphere(BoundingSphere) - Constructor for class com.jme3.bullet.collision.shapes.MultiSphere
-
Instantiate an eccentric sphere shape to match the specified BoundingSphere.
- MultiSphere(Vector3f[], float...) - Constructor for class com.jme3.bullet.collision.shapes.MultiSphere
-
Instantiate a multi-sphere shape with the specified centers and radii.
- MultiSphere(Vector3f, float) - Constructor for class com.jme3.bullet.collision.shapes.MultiSphere
-
Instantiate an eccentric sphere shape with the specified center and radius.
- MultiSphere(List<Vector3f>, List<Float>) - Constructor for class com.jme3.bullet.collision.shapes.MultiSphere
-
Instantiate a multi-sphere shape with the specified centers and radii.
- MultiSphere(RectangularSolid) - Constructor for class com.jme3.bullet.collision.shapes.MultiSphere
-
Instantiate a 4-sphere shape to fill the specified RectangularSolid.
- MultiSphere(RectangularSolid, float) - Constructor for class com.jme3.bullet.collision.shapes.MultiSphere
-
Instantiate a 2-sphere shape to approximate the specified RectangularSolid.
- MyControlP - Class in jme3utilities.minie
-
Utility methods that operate on scene-graph controls/spatials/subtrees that may include physics controls.
- MyPco - Class in jme3utilities.minie
-
Utility methods that operate on physics collision objects.
- MyShape - Class in jme3utilities.minie
-
Utility methods for physics collision shapes.
N
- name() - Method in class com.jme3.bullet.animation.AttachmentLink
-
Unambiguously identify this link by name, within its DynamicAnimControl.
- name() - Method in class com.jme3.bullet.animation.BoneLink
-
Unambiguously identify this link by name, within its DynamicAnimControl.
- name() - Method in class com.jme3.bullet.animation.PhysicsLink
-
Unambiguously identify this link by name, within its DynamicAnimControl.
- name() - Method in class com.jme3.bullet.animation.TorsoLink
-
Unambiguously identify this link by name, within its DynamicAnimControl.
- nativeId() - Method in class com.jme3.bullet.NativePhysicsObject
-
Return the ID of the assigned native object, assuming that one is assigned.
- NativeIDs - Enum constant in enum class jme3utilities.minie.DumpFlags
-
native IDs of physics objects
- nativeIndex() - Method in enum class com.jme3.bullet.joints.motors.MotorParam
-
Determine the parameter's index in native code.
- NativeLibrary - Class in com.jme3.bullet.util
-
Static interface to the Libbulletjme native library.
- nativeMargin() - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Return the native collision margin of this shape.
- NativeMeshUtil - Class in com.jme3.bullet.util
-
A utility class for interfacing with Native Bullet.
- NativePhysicsObject - Class in com.jme3.bullet
-
An abstract class to represent a native (Bullet) physics object.
- NativePhysicsObject() - Constructor for class com.jme3.bullet.NativePhysicsObject
-
Instantiate with no tracker and no assigned native object.
- NativeSoftBodyUtil - Class in com.jme3.bullet.util
-
A utility class for interfacing with Native Bullet, specifically for soft bodies.
- needsCollision(PhysicsCollisionObject, PhysicsCollisionObject) - Method in class com.jme3.bullet.CollisionSpace
-
Callback to determine whether the specified objects should be allowed to collide.
- NegativeAppDataFilter - Class in jme3utilities.minie
-
A simple DebugAppStateFilter that selects any physics objects NOT associated with a specific application-data object.
- NegativeAppDataFilter(Object) - Constructor for class jme3utilities.minie.NegativeAppDataFilter
-
Instantiate a filter for the specified application-data object.
- New6Dof - Class in com.jme3.bullet.joints
-
A 6 degree-of-freedom Constraint based on Bullet's btGeneric6DofSpring2Constraint.
- New6Dof() - Constructor for class com.jme3.bullet.joints.New6Dof
-
No-argument constructor needed by SavableClassUtil.
- New6Dof(PhysicsRigidBody, PhysicsRigidBody, Vector3f, Vector3f, Matrix3f, Matrix3f, RotationOrder) - Constructor for class com.jme3.bullet.joints.New6Dof
-
Instantiate a double-ended New6Dof constraint with all rotation DOFs free and all translation DOFs locked.
- New6Dof(PhysicsRigidBody, Vector3f, Vector3f, Matrix3f, Matrix3f, RotationOrder) - Constructor for class com.jme3.bullet.joints.New6Dof
-
Instantiate a single-ended New6Dof constraint with all rotation DOFs free and all translation DOFs locked.
- newEmptySoftBody() - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Create an empty
btSoftBody
for this PhysicsSoftBody, using the pre-existing worldInfo. - NewHinge - Class in com.jme3.bullet.joints
-
A 3 degree-of-freedom Constraint that mimics ODE's Hinge2 joint, such as might be used to model one of the front wheels on a motor vehicle.
- NewHinge() - Constructor for class com.jme3.bullet.joints.NewHinge
-
No-argument constructor needed by SavableClassUtil.
- NewHinge(PhysicsRigidBody, PhysicsRigidBody, Vector3f, Vector3f, Vector3f) - Constructor for class com.jme3.bullet.joints.NewHinge
-
Instantiate a double-ended constraint.
- newInstance(PhysicsRigidBody, PhysicsRigidBody, Vector3f, Quaternion, RotationOrder) - Static method in class com.jme3.bullet.joints.New6Dof
-
Instantiate a double-ended New6Dof constraint with all rotation DOFs free and all translation DOFs locked at zero.
- nextFillMode() - Method in class vhacd4.Vhacd4Parameters
-
Advance the fill mode to the next value.
- NNCG - Enum constant in enum class com.jme3.bullet.SolverType
-
btNNCGConstraintSolver: using the Non-smooth Nonlinear Conjugate Gradient (NNCG) method
- NO_CONTACT_RESPONSE - Static variable in class com.jme3.bullet.collision.CollisionFlag
-
flag for an object with no contact response, such as a PhysicsGhostObject
- NoCone - Static variable in class com.jme3.bullet.SolverMode
-
disable implicit cone friction
- NodeDamping - Enum constant in enum class com.jme3.bullet.objects.infos.Cluster
-
node-damping coefficient (default=0, native field: m_ndamping)
- nodeIndex() - Method in class com.jme3.bullet.joints.Anchor
-
Return the index of the anchored node in body A.
- nodeLocation(int, Vector3f) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Copy the location of the indexed node.
- nodeMass(int) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Read the mass of the indexed node.
- nodeNormal(int, Vector3f) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Copy the normal vector of the indexed node.
- NodesInClusters - Enum constant in enum class jme3utilities.minie.DumpFlags
-
soft-body nodes in clusters
- NodesInSofts - Enum constant in enum class jme3utilities.minie.DumpFlags
-
nodes in soft bodies
- nodeVelocity(int, Vector3f) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Copy the velocity of the indexed node.
- none - Static variable in class com.jme3.bullet.collision.AfMode
-
no anisotropic friction (native name: CF_ANISOTROPIC_FRICTION_DISABLED)
- NoVelocityDependent - Static variable in class com.jme3.bullet.SolverMode
-
disable velocity-dependent friction direction
- numIterations() - Method in class com.jme3.bullet.SolverInfo
-
Determine the number of iterations (native field: m_numIterations).
O
- objectName(PhysicsCollisionObject) - Static method in class jme3utilities.minie.MyPco
-
Generate a name for the specified collision object.
- onCompletion(T) - Method in interface com.jme3.bullet.animation.CompletionListener
-
Callback invoked after the operation completes.
- onContactEnded(long) - Method in interface com.jme3.bullet.collision.ContactListener
-
Invoked immediately after a contact manifold is removed.
- onContactEnded(long) - Method in class com.jme3.bullet.DefaultContactManager
-
Invoked immediately after a contact manifold is destroyed.
- onContactEnded(long) - Method in class com.jme3.bullet.PhysicsSpace
-
Invoked by native code immediately after a contact manifold is destroyed.
- onContactProcessed(PhysicsCollisionObject, PhysicsCollisionObject, long) - Method in interface com.jme3.bullet.collision.ContactListener
-
Invoked immediately after a contact point is refreshed without being removed.
- onContactProcessed(PhysicsCollisionObject, PhysicsCollisionObject, long) - Method in class com.jme3.bullet.DefaultContactManager
-
Invoked immediately after a contact point is refreshed without being destroyed.
- onContactProcessed(PhysicsCollisionObject, PhysicsCollisionObject, long) - Method in class com.jme3.bullet.PhysicsSpace
-
Invoked by native code immediately after a contact point is refreshed without being destroyed.
- onContactStarted(long) - Method in interface com.jme3.bullet.collision.ContactListener
-
Invoked immediately after a contact manifold is created.
- onContactStarted(long) - Method in class com.jme3.bullet.DefaultContactManager
-
Invoked immediately after a contact manifold is created.
- onContactStarted(long) - Method in class com.jme3.bullet.PhysicsSpace
-
Invoked by native code immediately after a contact manifold is created.
- onDisable() - Method in class com.jme3.bullet.debug.BulletDebugAppState
-
Transition this state from enabled to disabled.
- onEnable() - Method in class com.jme3.bullet.debug.BulletDebugAppState
-
Transition this state from disabled to enabled.
- onGround() - Method in class com.jme3.bullet.control.CharacterControl
-
Test whether the character is on the ground.
- onGround() - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Test whether the character is on the ground.
- onGround() - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Test whether this character is on the ground.
- orientation(Quaternion) - Method in class com.jme3.bullet.MultiBodyLink
-
Determine the orientation of the link relative to its parent when Q=0.
- overrideIterations(int) - Method in class com.jme3.bullet.joints.Constraint
-
Override the number of iterations used to solve this Constraint.
- Overrides - Enum constant in enum class jme3utilities.minie.DumpFlags
-
material-parameter overrides in spatials
P
- pairTest(PhysicsCollisionObject, PhysicsCollisionObject, PhysicsCollisionListener) - Method in class com.jme3.bullet.CollisionSpace
-
Perform a pair test.
- PARALLEL - Enum constant in enum class com.jme3.bullet.BulletAppState.ThreadingType
-
Parallel threaded mode: physics update and rendering are executed in parallel, update order is maintained.
- parent2Link(Vector3f) - Method in class com.jme3.bullet.MultiBodyLink
-
Determine the offset of the link's center relative to its parent's center for a planar joint.
- parent2Pivot(Vector3f) - Method in class com.jme3.bullet.MultiBodyLink
-
Determine the offset from the parent's center to the pivot for a non-planar joint.
- parseId(String) - Static method in class jme3utilities.minie.MyPco
-
Parse the ID of a collision object from its name.
- parseNativeId(String) - Static method in class jme3utilities.minie.MyShape
-
Parse the native ID of a shape from its String representation.
- partId(int) - Method in class com.jme3.bullet.collision.shapes.infos.BoundingValueHierarchy
-
Return the part index of the specified node.
- partIndex() - Method in class com.jme3.bullet.collision.PhysicsRayTestResult
-
Read the part index at the point of contact.
- partIndex() - Method in class com.jme3.bullet.collision.PhysicsSweepTestResult
-
Return the part index at the point of contact.
- Pcos - Enum constant in enum class jme3utilities.minie.DumpFlags
-
collision objects in physics spaces
- PcoType - Class in com.jme3.bullet.collision
-
Named constants for types of PhysicsCollisionObject.
- penetrationDepthSolver() - Method in class com.jme3.bullet.CollisionConfiguration
-
Return which penetration-depth solver is used.
- PersistentManifolds - Class in com.jme3.bullet.collision
-
Utility class to access fields of Bullet's
btPersistentManifold
class. - PGS - Enum constant in enum class com.jme3.bullet.SolverType
-
btSolveProjectedGaussSeidel: slow MLCP direct solver using projected Gauss-Seidel (PGS) for debug/learning purposes
- PhysicsBody - Class in com.jme3.bullet.objects
-
The abstract base class for rigid bodies and soft bodies.
- PhysicsBody() - Constructor for class com.jme3.bullet.objects.PhysicsBody
-
Instantiate a PhysicsBody.
- PhysicsCharacter - Class in com.jme3.bullet.objects
-
A collision object for simplified character simulation, based on Bullet's
btKinematicCharacterController
. - PhysicsCharacter() - Constructor for class com.jme3.bullet.objects.PhysicsCharacter
-
No-argument constructor needed by SavableClassUtil.
- PhysicsCharacter(ConvexShape, float) - Constructor for class com.jme3.bullet.objects.PhysicsCharacter
-
Instantiate a responsive character with the specified CollisionShape and step height.
- PhysicsCollisionEvent - Class in com.jme3.bullet.collision
-
Describe a point of contact between 2 collision objects in a PhysicsSpace, based on Bullet's btManifoldPoint.
- PhysicsCollisionEvent(PhysicsCollisionObject, PhysicsCollisionObject, long) - Constructor for class com.jme3.bullet.collision.PhysicsCollisionEvent
-
Instantiate an event.
- PhysicsCollisionGroupListener - Interface in com.jme3.bullet.collision
-
Interface to receive notifications whenever an object in a particular collision group is about to collide.
- PhysicsCollisionListener - Interface in com.jme3.bullet.collision
-
Interface to receive notifications when 2 collision objects collide.
- PhysicsCollisionObject - Class in com.jme3.bullet.collision
-
The abstract base class for collision objects based on Bullet's
btCollisionObject
. - PhysicsCollisionObject() - Constructor for class com.jme3.bullet.collision.PhysicsCollisionObject
-
Instantiate a collision object with no tracker and no assigned native object.
- PhysicsControl - Interface in com.jme3.bullet.control
-
An interface for a scene-graph control that links physics object(s) to a Spatial.
- PhysicsDescriber - Class in jme3utilities.minie
-
Generate compact textual descriptions of physics objects for debugging purposes.
- PhysicsDescriber() - Constructor for class jme3utilities.minie.PhysicsDescriber
-
Instantiate a describer with the default separator.
- PhysicsDumper - Class in jme3utilities.minie
-
Dump Minie data structures for debugging purposes.
- PhysicsDumper() - Constructor for class jme3utilities.minie.PhysicsDumper
-
Instantiate a PhysicsDumper that uses
System.out
for output. - PhysicsDumper(PrintStream) - Constructor for class jme3utilities.minie.PhysicsDumper
-
Instantiate a PhysicsDumper that uses the specified output stream.
- PhysicsGhostObject - Class in com.jme3.bullet.objects
-
A collision object for intangibles, based on Bullet's
btPairCachingGhostObject
. - PhysicsGhostObject() - Constructor for class com.jme3.bullet.objects.PhysicsGhostObject
-
No-argument constructor needed by SavableClassUtil.
- PhysicsGhostObject(CollisionShape) - Constructor for class com.jme3.bullet.objects.PhysicsGhostObject
-
Instantiate a ghost object with the specified CollisionShape.
- PhysicsJoint - Class in com.jme3.bullet.joints
-
The abstract base class for physics joints based on Bullet's btTypedConstraint, btSoftBody::Anchor, or btSoftBody::Joint.
- PhysicsJoint() - Constructor for class com.jme3.bullet.joints.PhysicsJoint
-
Instantiate a PhysicsJoint.
- PhysicsLink - Class in com.jme3.bullet.animation
-
The abstract base class used by DynamicAnimControl to link pieces of a JME model to their corresponding collision objects in a ragdoll.
- PhysicsLink() - Constructor for class com.jme3.bullet.animation.PhysicsLink
-
No-argument constructor needed by SavableClassUtil.
- PhysicsRayTestResult - Class in com.jme3.bullet.collision
-
Represent the results of a Bullet ray test.
- PhysicsRigidBody - Class in com.jme3.bullet.objects
-
A collision object to simulate a rigid body, based on Bullet's
btRigidBody
. - PhysicsRigidBody() - Constructor for class com.jme3.bullet.objects.PhysicsRigidBody
-
No-argument constructor needed by SavableClassUtil.
- PhysicsRigidBody(CollisionShape) - Constructor for class com.jme3.bullet.objects.PhysicsRigidBody
-
Instantiate a responsive, dynamic body with mass=1 and the specified CollisionShape.
- PhysicsRigidBody(CollisionShape, float) - Constructor for class com.jme3.bullet.objects.PhysicsRigidBody
-
Instantiate a responsive dynamic or static body with the specified CollisionShape and mass.
- PhysicsSoftBody - Class in com.jme3.bullet.objects
-
A collision object to simulate a soft body, based on Bullet's btSoftBody.
- PhysicsSoftBody() - Constructor for class com.jme3.bullet.objects.PhysicsSoftBody
-
Instantiate an empty soft body.
- PhysicsSoftSpace - Class in com.jme3.bullet
-
A PhysicsSpace that supports soft bodies, with its own
btSoftRigidDynamicsWorld
. - PhysicsSoftSpace(PhysicsSpace.BroadphaseType) - Constructor for class com.jme3.bullet.PhysicsSoftSpace
-
Instantiate a PhysicsSoftSpace with a sequential-impulse solver.
- PhysicsSoftSpace(Vector3f, Vector3f, PhysicsSpace.BroadphaseType) - Constructor for class com.jme3.bullet.PhysicsSoftSpace
-
Instantiate a PhysicsSoftSpace with a sequential-impulse solver.
- PhysicsSoftSpace(Vector3f, Vector3f, PhysicsSpace.BroadphaseType, CollisionConfiguration) - Constructor for class com.jme3.bullet.PhysicsSoftSpace
-
Instantiate a PhysicsSoftSpace with a sequential-impulse solver.
- PhysicsSpace - Class in com.jme3.bullet
-
A CollisionSpace to simulate dynamic physics, with its own
btDiscreteDynamicsWorld
. - PhysicsSpace(PhysicsSpace.BroadphaseType) - Constructor for class com.jme3.bullet.PhysicsSpace
-
Instantiate a PhysicsSpace with sequential-impulse solvers.
- PhysicsSpace(Vector3f, Vector3f) - Constructor for class com.jme3.bullet.PhysicsSpace
-
Instantiate a PhysicsSpace with an AXIS_SWEEP_3 broadphase accelerator and sequential-impulse solvers.
- PhysicsSpace(Vector3f, Vector3f, PhysicsSpace.BroadphaseType) - Constructor for class com.jme3.bullet.PhysicsSpace
-
Instantiate a PhysicsSpace with sequential-impulse solvers.
- PhysicsSpace(Vector3f, Vector3f, PhysicsSpace.BroadphaseType, int) - Constructor for class com.jme3.bullet.PhysicsSpace
-
Instantiate a PhysicsSpace with the specified number of sequential-impulse solvers.
- PhysicsSpace(Vector3f, Vector3f, PhysicsSpace.BroadphaseType, int, CollisionConfiguration) - Constructor for class com.jme3.bullet.PhysicsSpace
-
Instantiate a PhysicsSpace with the specified number of sequential-impulse solvers.
- PhysicsSpace(Vector3f, Vector3f, PhysicsSpace.BroadphaseType, SolverType) - Constructor for class com.jme3.bullet.PhysicsSpace
-
Instantiate a PhysicsSpace with the specified contact-and-constraint solver.
- PhysicsSpace(Vector3f, Vector3f, PhysicsSpace.BroadphaseType, SolverType, CollisionConfiguration) - Constructor for class com.jme3.bullet.PhysicsSpace
-
Instantiate a PhysicsSpace with the specified contact-and-constraint solver.
- PhysicsSpace.BroadphaseType - Enum Class in com.jme3.bullet
-
Enumerate the available accelerators for broadphase collision detection.
- PhysicsSweepTestResult - Class in com.jme3.bullet.collision
-
Represent the results of a Bullet sweep test.
- physicsTick(PhysicsSpace, float) - Method in class com.jme3.bullet.animation.DacLinks
-
Callback from Bullet, invoked just after the physics has been stepped.
- physicsTick(PhysicsSpace, float) - Method in class com.jme3.bullet.BulletAppState
-
Callback invoked just after the physics has been stepped.
- physicsTick(PhysicsSpace, float) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Callback from Bullet, invoked just after the physics has been stepped.
- physicsTick(PhysicsSpace, float) - Method in interface com.jme3.bullet.PhysicsTickListener
-
Callback invoked just after the physics has been stepped.
- PhysicsTickListener - Interface in com.jme3.bullet
-
Callback interface from the physics thread, used to clear/apply forces.
- physicsTransform(Transform) - Method in class com.jme3.bullet.animation.AttachmentLink
-
Calculate a physics transform for the rigid body.
- physicsTransform(Transform) - Method in class com.jme3.bullet.animation.PhysicsLink
-
Calculate a physics transform for the rigid body (to match the skeleton bone).
- physicsTransform(Transform) - Method in class com.jme3.bullet.objects.infos.RigidBodyMotionState
-
Calculate the body's physics transform.
- PhysicsVehicle - Class in com.jme3.bullet.objects
-
A rigid body for simplified vehicle simulation based on Bullet's
btRaycastVehicle
. - PhysicsVehicle() - Constructor for class com.jme3.bullet.objects.PhysicsVehicle
-
No-argument constructor needed by SavableClassUtil.
- PhysicsVehicle(CollisionShape) - Constructor for class com.jme3.bullet.objects.PhysicsVehicle
-
Instantiate a responsive vehicle with the specified CollisionShape and mass=1.
- PhysicsVehicle(CollisionShape, float) - Constructor for class com.jme3.bullet.objects.PhysicsVehicle
-
Instantiate a responsive vehicle with the specified CollisionShape and mass.
- pinToSelf(PhysicsLink, PhysicsLink, Vector3f, Vector3f) - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Add an IK joint that will restrict the specified links to pivoting around each other.
- pinToWorld(PhysicsLink, boolean) - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Add an IK joint that restricts the specified link to rotating around a pin location.
- pinToWorld(PhysicsLink, Vector3f) - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Add an IK joint that restricts the specified link to rotating around the specified location.
- pivot2Link(Vector3f) - Method in class com.jme3.bullet.MultiBodyLink
-
Determine the offset from the pivot to this link's center for a non-planar joint.
- pivotA - Variable in class com.jme3.bullet.joints.Constraint
-
copy of the pivot location: in physics-space coordinates if bodyA is null, or else in A's scaled local coordinates
- pivotB - Variable in class com.jme3.bullet.joints.Constraint
-
copy of the pivot location: in physics-space coordinates if bodyB is null, or else in B's scaled local coordinates
- Planar - Enum constant in enum class com.jme3.bullet.MultiBodyJointType
-
planar joint (native name: ePlanar)
- PlaneCollisionShape - Class in com.jme3.bullet.collision.shapes
-
A planar collision shape based on Bullet's
btStaticPlaneShape
. - PlaneCollisionShape() - Constructor for class com.jme3.bullet.collision.shapes.PlaneCollisionShape
-
No-argument constructor needed by SavableClassUtil.
- PlaneCollisionShape(Plane) - Constructor for class com.jme3.bullet.collision.shapes.PlaneCollisionShape
-
Instantiate a plane shape defined by the specified plane.
- PlaneDmiListener - Class in com.jme3.bullet.util
-
A DebugMeshInitListener to add texture coordinates to (the debug mesh of) a PlaneCollisionShape object.
- PlaneDmiListener(float) - Constructor for class com.jme3.bullet.util.PlaneDmiListener
-
Instantiate a listener for the specified texture-square size.
- Point2PointJoint - Class in com.jme3.bullet.joints
-
A 3 degree-of-freedom joint based on Bullet's btPoint2PointConstraint.
- Point2PointJoint() - Constructor for class com.jme3.bullet.joints.Point2PointJoint
-
No-argument constructor needed by SavableClassUtil.
- Point2PointJoint(PhysicsRigidBody, PhysicsRigidBody, Vector3f, Vector3f) - Constructor for class com.jme3.bullet.joints.Point2PointJoint
-
Instantiate a double-ended Point2PointJoint.
- Point2PointJoint(PhysicsRigidBody, Vector3f) - Constructor for class com.jme3.bullet.joints.Point2PointJoint
-
Instantiate a single-ended Point2PointJoint where the constraint is already satisfied.
- Point2PointJoint(PhysicsRigidBody, Vector3f, Vector3f) - Constructor for class com.jme3.bullet.joints.Point2PointJoint
-
Instantiate a single-ended Point2PointJoint where the constraint might not be satisfied yet.
- PoseMatching - Enum constant in enum class com.jme3.bullet.objects.infos.Sbcp
-
pose-matching coefficient: how strongly the soft body will tend to return to its default pose (≥0, ≤1, default=0, native field: kMT)
- positionIterations() - Method in class com.jme3.bullet.objects.infos.SoftBodyConfig
-
Return the number of position-solver iterations (native field: piterations).
- postRebuild() - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
For use by subclasses.
- postRebuild() - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Invoked during a rebuild after the native object is created.
- postRender() - Method in class com.jme3.bullet.BulletAppState
-
Update this state after all rendering commands are flushed.
- pQueueTL - Static variable in class com.jme3.bullet.PhysicsSpace
-
first-in/first-out (FIFO) queue of physics tasks for each thread
- PreComposer - Class in com.jme3.bullet.animation
-
Helper control for DynamicAnimControl, to hide armature modifications from an AnimComposer.
- PreComposer() - Constructor for class com.jme3.bullet.animation.PreComposer
-
No-argument constructor needed by SavableClassUtil.
- prePhysicsTick(PhysicsSpace, float) - Method in class com.jme3.bullet.animation.DacLinks
-
Callback from Bullet, invoked just before the physics is stepped.
- prePhysicsTick(PhysicsSpace, float) - Method in class com.jme3.bullet.BulletAppState
-
Callback invoked just before the physics is stepped.
- prePhysicsTick(PhysicsSpace, float) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Callback from Bullet, invoked just before the physics is stepped.
- prePhysicsTick(PhysicsSpace, float) - Method in interface com.jme3.bullet.PhysicsTickListener
-
Callback invoked just before the physics is stepped.
- preRebuild() - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
For use by subclasses.
- Pressure - Enum constant in enum class com.jme3.bullet.objects.infos.Sbcp
-
pressure coefficient (default=0, native field: kPR)
- preTick(float) - Method in class com.jme3.bullet.animation.IKController
-
Apply forces, impulses, and torques to the rigid body.
- principalAxes(FloatBuffer, Transform, Vector3f) - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Calculates the coordinate transform to be applied to a rigid body in order for this shape to be centered on its center of mass and its principal axes to coincide with its local axes.
- Prismatic - Enum constant in enum class com.jme3.bullet.MultiBodyJointType
-
prismatic joint (native name: ePrismatic)
- proxyGroup() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Return the collision group of the collision object's broadphase proxy.
- proxyMask() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Return the collision mask of this object's broadphase proxy.
R
- radius(CollisionShape) - Static method in class jme3utilities.minie.MyShape
-
Determine the unscaled radius of the specified shape.
- RagdollCollisionListener - Interface in com.jme3.bullet.animation
-
Interface to receive notifications whenever a linked rigid body in a DynamicAnimControl collides with another physics object.
- RagUtils - Class in com.jme3.bullet.animation
-
Utility methods used by DynamicAnimControl and associated classes.
- randomizeConstraints() - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Randomize constraints to reduce solver bias.
- RandomOrder - Static variable in class com.jme3.bullet.SolverMode
-
randomize order
- RangeOfMotion - Class in com.jme3.bullet.animation
-
A range-of-motion preset for a ragdoll joint.
- RangeOfMotion() - Constructor for class com.jme3.bullet.animation.RangeOfMotion
-
Instantiate a preset with no motion allowed.
- RangeOfMotion(float) - Constructor for class com.jme3.bullet.animation.RangeOfMotion
-
Instantiate a preset with the specified symmetric range of motion.
- RangeOfMotion(float, float, float) - Constructor for class com.jme3.bullet.animation.RangeOfMotion
-
Instantiate a preset with the specified symmetric range of motion.
- RangeOfMotion(float, float, float, float, float, float) - Constructor for class com.jme3.bullet.animation.RangeOfMotion
-
Instantiate a preset with the specified range of motion.
- RangeOfMotion(int) - Constructor for class com.jme3.bullet.animation.RangeOfMotion
-
Instantiate a preset for rotation on a single axis.
- RangeOfMotion(Vector3f) - Constructor for class com.jme3.bullet.animation.RangeOfMotion
-
Instantiate a preset with no motion allowed.
- RaycastFill - Enum constant in enum class com.jme3.bullet.FillMode
-
use raycasting to distinguish inside from outside (native name: RAYCAST_FILL)
- rayTest(Vector3f, Vector3f) - Method in class com.jme3.bullet.CollisionSpace
-
Perform a ray-collision test (raycast) and sort the results by ascending hitFraction.
- rayTest(Vector3f, Vector3f, List<PhysicsRayTestResult>) - Method in class com.jme3.bullet.CollisionSpace
-
Perform a ray-collision test (raycast) and sort the results by ascending hitFraction.
- rayTestDp(Vec3d, Vec3d, List<PhysicsRayTestResult>) - Method in class com.jme3.bullet.CollisionSpace
-
Perform a ray-collision test (raycast) and sort the results by ascending hitFraction.
- RayTestFlag - Class in com.jme3.bullet
-
Named flags for use with a ray test.
- rayTestRaw(Vector3f, Vector3f) - Method in class com.jme3.bullet.CollisionSpace
-
Perform a ray-collision test (raycast) and return the results in arbitrary order.
- rayTestRaw(Vector3f, Vector3f, List<PhysicsRayTestResult>) - Method in class com.jme3.bullet.CollisionSpace
-
Perform a ray-collision test (raycast) and return the results in arbitrary order.
- read(JmeImporter) - Method in class com.jme3.bullet.animation.AttachmentLink
-
De-serialize this link from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.animation.BoneLink
-
De-serialize this link from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.animation.DacConfiguration
-
De-serialize this Control from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.animation.DacLinks
-
De-serialize this Control from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
De-serialize this Control from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.animation.IKController
-
De-serialize this controller from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.animation.IKJoint
-
De-serialize this joint from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.animation.LinkConfig
-
De-serialize this configuration from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.animation.PhysicsLink
-
De-serialize this link from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.animation.PreComposer
-
De-serialize this Control from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.animation.RangeOfMotion
-
De-serialize this preset from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.animation.TorsoLink
-
De-serialize this link from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
De-serialize the collision object from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.collision.shapes.Box2dShape
-
De-serialize the shape from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.collision.shapes.BoxCollisionShape
-
De-serialize the shape from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.collision.shapes.CapsuleCollisionShape
-
De-serialize the shape from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
De-serialize the shape from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
De-serialize the shape from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.collision.shapes.ConeCollisionShape
-
De-serialize the shape from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.collision.shapes.ConicalFrustum
-
De-serialize the shape from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.collision.shapes.Convex2dShape
-
De-serialize the shape from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.collision.shapes.CustomConvexShape
-
De-serialize the shape from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.collision.shapes.CylinderCollisionShape
-
De-serialize the shape from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.collision.shapes.EmptyShape
-
De-serialize the shape from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.collision.shapes.GImpactCollisionShape
-
De-serialize the shape from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.collision.shapes.HeightfieldCollisionShape
-
De-serialize the shape from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.collision.shapes.HullCollisionShape
-
De-serialize the shape from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.collision.shapes.infos.BoundingValueHierarchy
-
De-serialize this mesh from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.collision.shapes.infos.ChildCollisionShape
-
De-serialize this child from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.collision.shapes.infos.CompoundMesh
-
De-serialize this mesh from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.collision.shapes.infos.IndexedMesh
-
De-serialize this mesh from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.collision.shapes.MeshCollisionShape
-
De-serialize the shape from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.collision.shapes.MinkowskiSum
-
De-serialize the shape from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.collision.shapes.MultiSphere
-
De-serialize the shape from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.collision.shapes.PlaneCollisionShape
-
De-serialize the shape from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.collision.shapes.SimplexCollisionShape
-
De-serialize the shape from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.collision.shapes.SphereCollisionShape
-
De-serialize the shape from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.collision.shapes.SphericalSegment
-
De-serialize the shape from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.control.AbstractPhysicsControl
-
De-serialize this Control from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
De-serialize this Control from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.control.CharacterControl
-
De-serialize this Control from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.control.GhostControl
-
De-serialize this Control from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.control.JoinedBodyControl
-
De-serialize this Control from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.control.RigidBodyControl
-
De-serialize this Control from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.control.SoftBodyControl
-
De-serialize this Control from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.control.VehicleControl
-
De-serialize this Control from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.debug.AbstractPhysicsDebugControl
-
De-serialize this Control from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.joints.Anchor
-
De-serialize this joint from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.joints.ConeJoint
-
De-serialize this joint from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.joints.Constraint
-
De-serialize this Constraint from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.joints.GearJoint
-
De-serialize this joint from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.joints.HingeJoint
-
De-serialize this joint from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.joints.New6Dof
-
De-serialize this Constraint from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.joints.NewHinge
-
De-serialize this Constraint from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.joints.PhysicsJoint
-
De-serialize this joint from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.joints.Point2PointJoint
-
De-serialize this joint from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.joints.SixDofJoint
-
De-serialize this joint from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.joints.SixDofSpringJoint
-
De-serialize this joint from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.joints.SliderJoint
-
De-serialize this joint from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.joints.SoftAngularJoint
-
De-serialize this joint from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.joints.SoftLinearJoint
-
De-serialize this joint from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.joints.SoftPhysicsJoint
-
De-serialize this joint from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.MultiBody
-
De-serialize this object from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.MultiBodyLink
-
De-serialize this object from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.objects.infos.CharacterController
-
De-serialize this controller from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.objects.infos.RigidBodyMotionState
-
De-serialize this state from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.objects.infos.SoftBodyConfig
-
De-serialize this config from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.objects.infos.SoftBodyMaterial
-
De-serialize this material from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.objects.infos.VehicleTuning
-
De-serialize these parameters from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.objects.MultiBodyCollider
-
De-serialize this object from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
De-serialize this character from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.objects.PhysicsGhostObject
-
De-serialize this object from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
De-serialize this body from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
De-serialize this body from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
De-serialize this vehicle from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.objects.VehicleWheel
-
De-serialize this wheel from the specified importer, for example when loading from a J3O file.
- read(JmeImporter) - Method in class com.jme3.bullet.SoftBodyWorldInfo
-
De-serialize this info from the specified importer, for example when loading from a J3O file.
- readConstraintProperties(InputCapsule) - Method in class com.jme3.bullet.joints.Constraint
-
Read common properties from a capsule.
- readJoints(InputCapsule) - Method in class com.jme3.bullet.objects.PhysicsBody
-
De-serialize joints from the specified InputCapsule, for example when loading from a J3O file.
- readPcoProperties(InputCapsule) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Read common properties from a capsule.
- readShapeProperties(InputCapsule) - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Read common properties from an
InputCapsule
. - readTransformArray(InputCapsule, String) - Static method in class com.jme3.bullet.animation.RagUtils
-
Read an array of transforms from an input capsule.
- reassignNativeId(long) - Method in class com.jme3.bullet.NativePhysicsObject
-
Assign a tracked native object to this instance, unassigning (but not freeing) any previously assigned one.
- rebuild() - Method in class com.jme3.bullet.animation.DacLinks
-
Rebuild the ragdoll.
- rebuildRigidBody() - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Rebuild the rigid body with a new native object.
- recalculateAabb() - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Recalculate this shape's bounding box if necessary.
- recalculateAabb() - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Recalculate this shape's bounding box if necessary.
- recalculateAabb() - Method in class com.jme3.bullet.collision.shapes.GImpactCollisionShape
-
Recalculate this shape's bounding box if necessary.
- recalculateAabb() - Method in class com.jme3.bullet.collision.shapes.HullCollisionShape
-
Recalculate the shape's bounding box if necessary.
- recalculateAabb() - Method in class com.jme3.bullet.collision.shapes.MeshCollisionShape
-
Recalculate this shape's bounding box if necessary.
- recalculateAabb() - Method in class com.jme3.bullet.collision.shapes.MultiSphere
-
Recalculate the shape's bounding box if necessary.
- recalculateAabb() - Method in class com.jme3.bullet.collision.shapes.SimplexCollisionShape
-
Recalculate the shape's bounding box if necessary.
- relativeTolerance() - Method in class com.jme3.bullet.animation.DacConfiguration
-
Return the relative tolerance for comparing scale factors.
- relativeTransform(Spatial, Node, Transform) - Static method in class com.jme3.bullet.animation.RagUtils
-
Calculate a coordinate transform for the specified Spatial relative to a specified ancestor node.
- release() - Method in class com.jme3.bullet.animation.AttachmentLink
-
Release the attached model.
- releaseAllClusters() - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Release all clusters.
- releaseCluster(int) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Release the indexed cluster.
- remove(Object) - Method in class com.jme3.bullet.CollisionSpace
-
Remove the specified object from the space.
- remove(Object) - Method in class com.jme3.bullet.MultiBodySpace
-
Remove the specified object from this space.
- remove(Object) - Method in class com.jme3.bullet.PhysicsSpace
-
Remove the specified object from the space.
- removeAll(Spatial) - Method in class com.jme3.bullet.PhysicsSpace
-
Remove all physics controls in the specified subtree of the scene graph from the space (e.g.
- removeChildShape(CollisionShape) - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Purge all references to the specified child shape from this shape.
- removeCollideWithGroup(int) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Remove collision groups from the set with which this object can collide.
- removeCollisionGroupListener(int) - Method in class com.jme3.bullet.CollisionSpace
-
De-register the specified collision-group listener.
- removeCollisionListener(PhysicsCollisionListener) - Method in interface com.jme3.bullet.ContactManager
-
De-register the specified listener for new contacts.
- removeCollisionListener(PhysicsCollisionListener) - Method in class com.jme3.bullet.DefaultContactManager
-
De-register the specified listener for new contacts.
- removeCollisionListener(PhysicsCollisionListener) - Method in class com.jme3.bullet.PhysicsSpace
-
De-register the specified listener for new contacts.
- removeCollisionObject(PhysicsCollisionObject) - Method in class com.jme3.bullet.CollisionSpace
-
Remove the specified collision object from the space.
- removeCollisionObject(PhysicsCollisionObject) - Method in class com.jme3.bullet.DeformableSpace
-
Remove the specified collision object from this space.
- removeCollisionObject(PhysicsCollisionObject) - Method in class com.jme3.bullet.PhysicsSoftSpace
-
Remove the specified collision object from this space.
- removeCollisionObject(PhysicsCollisionObject) - Method in class com.jme3.bullet.PhysicsSpace
-
Remove the specified collision object from the space.
- removeContactListener(ContactListener) - Method in interface com.jme3.bullet.ContactManager
-
De-register the specified listener for immediate contact notifications.
- removeContactListener(ContactListener) - Method in class com.jme3.bullet.DefaultContactManager
-
De-register the specified listener for immediate contact notifications.
- removeContactListener(ContactListener) - Method in class com.jme3.bullet.PhysicsSpace
-
De-register the specified listener for immediate contact notifications.
- removeException(Object) - Method in class jme3utilities.minie.FilterAll
-
Remove an object from the exceptions list.
- removeFromIgnoreList(PhysicsCollisionObject) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Remove a collision object from this object's ignore list and vice versa.
- removeIKController(IKController) - Method in class com.jme3.bullet.animation.PhysicsLink
-
Remove an IK controller.
- removeJoint(PhysicsJoint) - Method in class com.jme3.bullet.objects.PhysicsBody
-
Do not invoke directly! Joints are removed automatically when destroyed.
- removeJoint(PhysicsJoint) - Method in class com.jme3.bullet.PhysicsSpace
-
Remove the specified PhysicsJoint from the space.
- removeMultiBody(MultiBody) - Method in class com.jme3.bullet.MultiBodySpace
-
Remove the specified MultiBody and all its colliders.
- removeNonPhysicsControls(Spatial) - Static method in class jme3utilities.minie.MyControlP
-
Remove all non-physics controls from the specified subtree of the scene graph.
- removeOngoingCollisionListener(PhysicsCollisionListener) - Method in interface com.jme3.bullet.ContactManager
-
De-register the specified listener for ongoing contacts.
- removeOngoingCollisionListener(PhysicsCollisionListener) - Method in class com.jme3.bullet.DefaultContactManager
-
De-register the specified listener for ongoing contacts.
- removeOngoingCollisionListener(PhysicsCollisionListener) - Method in class com.jme3.bullet.PhysicsSpace
-
De-register the specified listener for ongoing contacts.
- removePhysics() - Method in class com.jme3.bullet.animation.DacLinks
-
Remove all managed physics objects from the PhysicsSpace.
- removePhysics() - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Remove all managed physics objects from the PhysicsSpace.
- removePhysics() - Method in class com.jme3.bullet.control.AbstractPhysicsControl
-
Remove all managed physics objects from the PhysicsSpace.
- removePhysics() - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Remove all managed physics objects from the PhysicsSpace.
- removePhysics() - Method in class com.jme3.bullet.control.CharacterControl
-
Remove all managed physics objects from the PhysicsSpace.
- removePhysics() - Method in class com.jme3.bullet.control.JoinedBodyControl
-
Remove all managed physics objects from the PhysicsSpace.
- removePhysics() - Method in class com.jme3.bullet.control.SoftBodyControl
-
Remove all managed physics objects from the PhysicsSpace.
- removeProgressListener(VHACDProgressListener) - Static method in class vhacd.VHACD
-
De-register the specified progress listener.
- removeProgressListener(VHACDProgressListener) - Static method in class vhacd4.Vhacd4
-
De-register the specified progress listener.
- removeShapeFromCache(long) - Static method in class com.jme3.bullet.util.DebugShapeFactory
-
Forget all previously generated debug meshes for the identified shape.
- removeSpatialData(Spatial) - Method in class com.jme3.bullet.animation.DacLinks
-
Remove spatial-dependent data.
- removeSpatialData(Spatial) - Method in class com.jme3.bullet.control.AbstractPhysicsControl
-
Destroy spatial-dependent data.
- removeSpatialData(Spatial) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Destroy spatial-dependent data.
- removeSpatialData(Spatial) - Method in class com.jme3.bullet.control.CharacterControl
-
Destroy spatial-dependent data.
- removeSpatialData(Spatial) - Method in class com.jme3.bullet.control.JoinedBodyControl
-
Destroy spatial-dependent data.
- removeSpatialData(Spatial) - Method in class com.jme3.bullet.control.SoftBodyControl
-
Destroy spatial-dependent data.
- removeTickListener(PhysicsTickListener) - Method in class com.jme3.bullet.PhysicsSpace
-
De-register the specified tick listener.
- removeWheel(int) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Remove a wheel.
- render(RenderManager) - Method in class com.jme3.bullet.BulletAppState
-
Render this state.
- render(RenderManager) - Method in class com.jme3.bullet.debug.BulletDebugAppState
-
Render this state.
- render(RenderManager, ViewPort) - Method in class com.jme3.bullet.control.AbstractPhysicsControl
-
Render this Control.
- render(RenderManager, ViewPort) - Method in class com.jme3.bullet.control.GhostControl
-
Render this Control.
- render(RenderManager, ViewPort) - Method in class com.jme3.bullet.control.RigidBodyControl
-
Render this Control.
- render(RenderManager, ViewPort) - Method in class com.jme3.bullet.control.VehicleControl
-
Render this Control.
- reset(PhysicsSpace) - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Reset this controller, including its velocity.
- reset(PhysicsSpace) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Reset this character, including its velocity.
- Reset - Enum constant in enum class com.jme3.bullet.animation.KinematicSubmode
-
forced to the pose defined by
setEndBoneTransforms()
- resetForward(Vector3f) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Alter the character's forward (+Z) direction, provided it's in dynamic mode.
- resetQuickprof() - Static method in class com.jme3.bullet.util.NativeLibrary
-
Reset Quickprof.
- resetRestingLengths() - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Set the resting lengths of all links to their current lengths.
- resetSuspension() - Method in class com.jme3.bullet.objects.infos.VehicleController
-
Reset the vehicle's suspension.
- resetSuspension() - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Reset this vehicle's suspension.
- restingLengthsScale() - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Read the scale factor for resting lengths.
- Revolute - Enum constant in enum class com.jme3.bullet.MultiBodyJointType
-
revolute joint (native name: eRevolute)
- rightAxisIndex() - Method in class com.jme3.bullet.objects.infos.VehicleController
-
Determine the index of the vehicle's right-side axis.
- rightAxisIndex() - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Determine the index of this vehicle's right-side axis.
- rigid - Static variable in class com.jme3.bullet.collision.PcoType
-
value for a PhysicsVehicle chassis or PhysicsRigidBody (native name: CO_RIGID_BODY)
- RigidBodyControl - Class in com.jme3.bullet.control
-
A PhysicsControl to link a PhysicsRigidBody to a Spatial.
- RigidBodyControl() - Constructor for class com.jme3.bullet.control.RigidBodyControl
-
No-argument constructor needed by SavableClassUtil.
- RigidBodyControl(float) - Constructor for class com.jme3.bullet.control.RigidBodyControl
-
Instantiate an enabled control.
- RigidBodyControl(CollisionShape) - Constructor for class com.jme3.bullet.control.RigidBodyControl
-
Instantiate an enabled Control with an active/responsive dynamic rigid body, mass=1, and the specified shape.
- RigidBodyControl(CollisionShape, float) - Constructor for class com.jme3.bullet.control.RigidBodyControl
-
Instantiate an enabled
Control
with a dynamic or static rigid body and the specified shape and mass. - RigidBodyMotionState - Class in com.jme3.bullet.objects.infos
-
The motion state (transform) of a rigid body, with thread-safe access.
- RigidBodyMotionState() - Constructor for class com.jme3.bullet.objects.infos.RigidBodyMotionState
-
Instantiate a motion state.
- RigidBodySnapshot - Class in com.jme3.bullet.objects.infos
-
Copy certain properties of a
PhysicsRigidBody
in order to re-apply them later. - RigidBodySnapshot(PhysicsRigidBody) - Constructor for class com.jme3.bullet.objects.infos.RigidBodySnapshot
-
Instantiate a snapshot of the specified body.
- RigidHardness - Enum constant in enum class com.jme3.bullet.objects.infos.Sbcp
-
contact hardness coefficient for dynamic rigid bodies (≥0, ≤1, default=1, native field: kCHR)
- rolling - Static variable in class com.jme3.bullet.collision.AfMode
-
anisotropic rolling friction mode (native name: CF_ANISOTROPIC_ROLLING_FRICTION)
- rotate(Matrix3f) - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Apply the specified rotation (in the parent's coordinate system) to each child.
- RotationalLimitMotor - Class in com.jme3.bullet.joints.motors
-
A motor based on Bullet's btRotationalLimitMotor, used to control the rotation of a SixDofJoint.
- RotationalLimitMotor(long) - Constructor for class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Instantiate a motor.
- RotationMotor - Class in com.jme3.bullet.joints.motors
-
A single-axis motor based on Bullet's btRotationalLimitMotor2, used to control the rotation of a New6Dof constraint.
- RotationMotor(long) - Constructor for class com.jme3.bullet.joints.motors.RotationMotor
-
Instantiate a motor.
- rotationOrder() - Method in class com.jme3.bullet.animation.LinkConfig
-
Read the order in which axis rotations will be applied.
- RotationOrder - Enum Class in com.jme3.bullet
-
Enumerate the orders in which axis rotations can be applied (native enum: RotateOrder).
S
- saveCurrentPose() - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Record the current bone transforms for use in a kinematic reset.
- Sbcp - Enum Class in com.jme3.bullet.objects.infos
-
Enumerate the float-valued parameters in a SoftBodyConfig.
- scale - Variable in class com.jme3.bullet.collision.shapes.CollisionShape
-
copy of the scale factors, one for each local axis
- scaledVolume() - Method in class com.jme3.bullet.collision.shapes.BoxCollisionShape
-
Estimate the volume of the collision shape, including scale and margin.
- scaledVolume() - Method in class com.jme3.bullet.collision.shapes.CapsuleCollisionShape
-
Estimate the volume of the shape, including scale and margin.
- scaledVolume() - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Estimate the volume of this shape, including scale and margin.
- scaledVolume() - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Estimate the volume of this shape, including scale and margin.
- scaledVolume() - Method in class com.jme3.bullet.collision.shapes.ConicalFrustum
-
Estimate the volume of the collision shape, including scale and margin.
- scaledVolume() - Method in class com.jme3.bullet.collision.shapes.ConvexShape
-
Estimate the volume of this shape, including scale and margin.
- scaledVolume() - Method in class com.jme3.bullet.collision.shapes.EmptyShape
-
Return the volume of the shape, including scale and margin.
- scaledVolume() - Method in class com.jme3.bullet.collision.shapes.MultiSphere
-
Estimate the volume of the shape, including scale and margin.
- scaledVolume() - Method in class com.jme3.bullet.collision.shapes.SphereCollisionShape
-
Estimate the volume of this shape, including scale and margin.
- scaledVolume() - Method in class com.jme3.bullet.collision.shapes.SphericalSegment
-
Estimate the volume of the collision shape, including scale and margin.
- SDF_MDF - Static variable in class com.jme3.bullet.objects.infos.ConfigFlag
-
enable the GJK-based handler for multibody-versus-deformable face collisions
- SDF_RD - Static variable in class com.jme3.bullet.objects.infos.ConfigFlag
-
enable the SDF-based handler for rigid-versus-deformable collisions
- SDF_RDF - Static variable in class com.jme3.bullet.objects.infos.ConfigFlag
-
enable the GJK-based handler for rigid-versus-deformable face collisions
- SDF_RDN - Static variable in class com.jme3.bullet.objects.infos.ConfigFlag
-
enable the SDF-based handler for rigid-versus-deformable node collisions
- SDF_RS - Static variable in class com.jme3.bullet.objects.infos.ConfigFlag
-
enable the SDF-based handler for rigid-versus-soft collisions
- SelfImpulse - Enum constant in enum class com.jme3.bullet.objects.infos.Cluster
-
self-collision impulse factor (default=0.01, native field: m_selfCollisionImpulseFactor)
- Separate - Static variable in class com.jme3.bullet.SolverMode
-
friction separate
- SEQUENTIAL - Enum constant in enum class com.jme3.bullet.BulletAppState.ThreadingType
-
Default mode: user update, physics update, and rendering happen sequentially.
- serialize() - Method in class com.jme3.bullet.collision.shapes.infos.BoundingValueHierarchy
-
Serialize the hierarchy to a byte array.
- serializeBvh() - Method in class com.jme3.bullet.collision.shapes.MeshCollisionShape
-
Serialize the BVH to a byte array.
- ServoTarget - Enum constant in enum class com.jme3.bullet.joints.motors.MotorParam
-
servo's target (m_servoTarget, default=0)
- set(MotorParam, float) - Method in class com.jme3.bullet.joints.motors.RotationMotor
-
Alter the specified parameter.
- set(MotorParam, int, float) - Method in class com.jme3.bullet.joints.New6Dof
-
Alter the specified parameter for the indexed degree of freedom.
- set(MotorParam, Vector3f) - Method in class com.jme3.bullet.joints.motors.TranslationMotor
-
Alter the specified parameter of this motor.
- set(Cluster, int, float) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Alter the specified parameter of the indexed cluster.
- set(Sbcp, float) - Method in class com.jme3.bullet.objects.infos.SoftBodyConfig
-
Alter the specified parameter.
- setAccumulatedImpulse(float) - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Alter the accumulated impulse (native field: m_accumulatedImpulse).
- setAccumulatedImpulse(Vector3f) - Method in class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
Alter the accumulated impulse (native field: m_accumulatedImpulse).
- setAccuracy(float) - Method in class com.jme3.bullet.PhysicsSpace
-
Alter the accuracy (time step used when maxSubSteps>0).
- setACDMode(ACDMode) - Method in class vhacd.VHACDParameters
-
Set approximate convex decomposition mode (native field: m_mode).
- setActivationState(long, int) - Static method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Alter the activation state of the collision object.
- setAerodynamics(Aero) - Method in class com.jme3.bullet.objects.infos.SoftBodyConfig
-
Alter the aerodynamics model.
- setAirDensity(float) - Method in class com.jme3.bullet.SoftBodyWorldInfo
-
Alter the air density.
- setAlpha(double) - Method in class vhacd.VHACDParameters
-
Set bias toward clipping along symmetry planes (native field: m_alpha).
- setAngularDamping(float) - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Alter the character's angular damping.
- setAngularDamping(float) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Alter this character's angular damping.
- setAngularDamping(float) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Alter the body's angular damping.
- setAngularFactor(float) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Alter the body's angular factor.
- setAngularFactor(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Alter the body's angular factors, used to scale applied torques.
- setAngularLowerLimit(Vector3f) - Method in class com.jme3.bullet.joints.SixDofJoint
-
Alter the joint's lower limits for rotation of all 3 axes.
- setAngularOnly(boolean) - Method in class com.jme3.bullet.joints.ConeJoint
-
Alter whether this joint is angular-only.
- setAngularOnly(boolean) - Method in class com.jme3.bullet.joints.HingeJoint
-
Alter whether this joint is angular-only, meaning no constraints on translation.
- setAngularSleepingThreshold(float) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Alter the body's angular-motion sleeping threshold.
- setAngularStiffness(float) - Method in class com.jme3.bullet.objects.infos.SoftBodyMaterial
-
Alter the angular-stiffness coefficient (native field: m_kAST).
- setAngularUpperLimit(Vector3f) - Method in class com.jme3.bullet.joints.SixDofJoint
-
Alter the joint's upper limits for rotation of all 3 axes.
- setAngularVelocity(Vector3f) - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Alter the character's angular velocity.
- setAngularVelocity(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Alter this character's angular velocity.
- setAngularVelocity(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Alter the body's angular velocity.
- setAngularVelocityDp(Vec3d) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Alter the body's angular velocity.
- setAngularVelocityFilter(BulletDebugAppState.DebugAppStateFilter) - Method in class com.jme3.bullet.debug.BulletDebugAppState
-
Alter which angular velocities are visualized.
- setAngularVelocityFilter(BulletDebugAppState.DebugAppStateFilter) - Method in class com.jme3.bullet.debug.DebugConfiguration
-
Alter which angular velocities are included in the visualization.
- setAnisotropicFriction(Vector3f, int) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Alter this object's anisotropic friction (native field: m_anisotropicFriction).
- setApplicationData(Object) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Associate application-specific data with this collision object.
- setAppliedImpulse(long, float) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Alter the applied impulse of the specified point (native field: m_appliedImpulse).
- setAppliedImpulseLateral1(long, float) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Alter the applied lateral impulse #1 of the specified point (native field: m_appliedImpulseLateral1).
- setAppliedImpulseLateral2(long, float) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Alter the applied lateral impulse #2 of the specified point (native field: m_appliedImpulseLateral2).
- setApplyLocal(boolean) - Method in class com.jme3.bullet.objects.VehicleWheel
-
Alter whether physics coordinates should match the local transform of the Spatial.
- setApplyPhysicsLocal(boolean) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Alter whether physics-space coordinates should match the spatial's local coordinates.
- setApplyPhysicsLocal(boolean) - Method in class com.jme3.bullet.control.AbstractPhysicsControl
-
Alter whether physics-space coordinates should match the Spatial's local coordinates.
- setApplyPhysicsLocal(boolean) - Method in class com.jme3.bullet.control.GhostControl
-
Alter whether physics-space coordinates should match the spatial's local coordinates.
- setApplyPhysicsLocal(boolean) - Method in class com.jme3.bullet.control.RigidBodyControl
-
Alter whether physics-space coordinates should match the spatial's local coordinates.
- setApplyPhysicsLocal(boolean) - Method in class com.jme3.bullet.control.VehicleControl
-
Alter whether physics-space coordinates should match the spatial's local coordinates.
- setApplyPhysicsLocal(boolean) - Method in class com.jme3.bullet.objects.infos.RigidBodyMotionState
-
Alter whether physics-space coordinates should match the spatial's local coordinates.
- setApplyPhysicsLocal(Control, boolean) - Static method in class jme3utilities.minie.MyControlP
-
Alter whether the specified SGC applies physics coordinates to its spatial's local translation.
- setApplyScale(boolean) - Method in class com.jme3.bullet.control.GhostControl
-
Alter whether the collision-shape scale should match the spatial's scale.
- setApplyScale(boolean) - Method in class com.jme3.bullet.control.RigidBodyControl
-
Alter whether the collision-shape scale should match the spatial's scale.
- setAsync(boolean) - Method in class vhacd4.Vhacd4Parameters
-
Alter whether V-HACD should run on a new thread (native field: m_asyncACD).
- setAttachmentConfig(String, LinkConfig) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Alter the configuration of the attachment associated with the named bone.
- setAttachmentConfig(String, LinkConfig) - Method in class com.jme3.bullet.animation.DacLinks
-
Alter the configuration of the attachment associated with the named bone.
- setAttachmentMass(String, float) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Alter the mass of the attachment associated with the named bone.
- setAttachmentMass(String, float) - Method in class com.jme3.bullet.animation.DacLinks
-
Alter the mass of the attachment associated with the named bone.
- setAxis(Vector3f) - Method in class com.jme3.bullet.joints.SoftAngularJoint
-
Alter the joint axis.
- setAxisA(Vector3f) - Method in class com.jme3.bullet.joints.GearJoint
-
Alter the A body's axis of rotation.
- setAxisArrowLength(float) - Method in class com.jme3.bullet.debug.DebugConfiguration
-
Alter the length of axis arrows.
- setAxisB(Vector3f) - Method in class com.jme3.bullet.joints.GearJoint
-
Alter the B body's axis of rotation.
- setAxisLineWidth(float) - Method in class com.jme3.bullet.debug.DebugConfiguration
-
Alter the line width for axis arrows.
- setBaseAngularVelocity(Vector3f) - Method in class com.jme3.bullet.MultiBody
-
Alter the angular velocity of the base.
- setBaseLocation(Vector3f) - Method in class com.jme3.bullet.MultiBody
-
Alter the location of the base's center of mass.
- setBaseOrientation(Quaternion) - Method in class com.jme3.bullet.MultiBody
-
Alter the orientation of the base.
- setBaseTransform(Transform) - Method in class com.jme3.bullet.MultiBody
-
Alter the transform of the base.
- setBaseVelocity(Vector3f) - Method in class com.jme3.bullet.MultiBody
-
Alter the linear velocity of the base.
- setBeta(double) - Method in class vhacd.VHACDParameters
-
Set bias toward clipping along revolution axes (native field: m_beta).
- setBlendListener(CompletionListener<DynamicAnimControl>) - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Replace the current blend listener.
- setBlueArrow(Vector3f, Vector3f) - Method in class com.jme3.bullet.debug.DebugTools
-
Alter the location and extent of the blue arrow.
- setBodyA(PhysicsBody) - Method in class com.jme3.bullet.joints.PhysicsJoint
-
Specify the body at the joint's "A" end.
- setBodyB(PhysicsBody) - Method in class com.jme3.bullet.joints.PhysicsJoint
-
Specify the body at the joint's "B" end.
- setBoundingBoxFilter(BulletDebugAppState.DebugAppStateFilter) - Method in class com.jme3.bullet.debug.BulletDebugAppState
-
Alter which bounding boxes are visualized.
- setBoundingBoxFilter(BulletDebugAppState.DebugAppStateFilter) - Method in class com.jme3.bullet.debug.DebugConfiguration
-
Alter which bounding boxes are included in the visualization.
- setBreakingImpulseThreshold(float) - Method in class com.jme3.bullet.joints.Constraint
-
Alter the breaking impulse threshold.
- setBroadphaseType(PhysicsSpace.BroadphaseType) - Method in class com.jme3.bullet.BulletAppState
-
Alter the broadphase type the PhysicsSpace will use.
- setCamera(Camera) - Method in class com.jme3.bullet.debug.DebugConfiguration
-
Alter which Camera is used for (debug) visualization.
- setCcdMotionThreshold(float) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Alter the amount of motion required to trigger continuous collision detection (CCD) (native field: m_ccdMotionThreshold).
- setCcdSweptSphereRadius(float) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Alter the continuous collision detection (CCD) swept-sphere radius for this object (native field: m_ccdSweptSphereRadius).
- setCcdWithStaticOnly(boolean) - Method in class com.jme3.bullet.PhysicsSpace
-
Alter whether CCD checks for collisions with static and kinematic bodies (native field: m_ccdWithStaticOnly).
- setCFM(float) - Method in class com.jme3.bullet.joints.SoftPhysicsJoint
-
Set the constraint force mixing coefficient (aka CFM).
- setChildTransform(CollisionShape, Transform) - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Alter the local transform of the specified child CollisionShape.
- setClusterFilter(BulletDebugAppState.DebugAppStateFilter) - Method in class com.jme3.bullet.debug.SoftDebugAppState
-
Alter which soft-body clusters are visualized.
- setClusterIterations(int) - Method in class com.jme3.bullet.objects.infos.SoftBodyConfig
-
Alter the number of cluster-solver iterations (native field: citerations).
- setCollideWithGroups(int) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Directly alter the collision groups with which this object can collide.
- setCollideWithGroups(int) - Method in class com.jme3.bullet.MultiBody
-
Directly alter the collision groups with which this MultiBody can collide.
- setCollisionBetweenLinkedBodies(boolean) - Method in class com.jme3.bullet.joints.Constraint
-
Handle/ignore collisions between the ends of a double-ended joint.
- setCollisionConfiguration(CollisionConfiguration) - Method in class com.jme3.bullet.BulletAppState
-
Replace the collision configuration that will be used to instantiate the PhysicsSpace.
- setCollisionFlags(int, int...) - Method in class com.jme3.bullet.objects.infos.SoftBodyConfig
-
Alter the collision flags (default=SDF_RS).
- setCollisionFlags(long, int) - Static method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Alter the collision flags of the collision object (native field: m_collisionFlags).
- setCollisionGroup(int) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Alter which collision group this object belongs to.
- setCollisionGroup(int) - Method in class com.jme3.bullet.MultiBody
-
Alter which collision group this MultiBody belongs to.
- setCollisionShape(CollisionShape) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Apply the specified shape to the collision object.
- setCollisionShape(CollisionShape) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Apply the specified CollisionShape to this character.
- setCollisionShape(CollisionShape) - Method in class com.jme3.bullet.objects.PhysicsGhostObject
-
Apply the specified CollisionShape to this object.
- setCollisionShape(CollisionShape) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Apply the specified CollisionShape to the body.
- setCombinedFriction(long, float) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Alter the combined friction of the specified point (native field: m_combinedFriction).
- setCombinedRestitution(long, float) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Alter the combined restitution of the specified point (native field: m_combinedRestitution).
- setCombinedRollingFriction(long, float) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Alter the combined rolling friction of the specified point (native field: m_combinedRollingFriction).
- setCombinedSpinningFriction(long, float) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Alter the combined spinning friction of the specified point (native field: m_combinedSpinningFriction).
- setConfig(String, LinkConfig) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Alter the configuration of the named bone/torso.
- setContactCalcArea3Points(boolean) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Alter the number of points used to calculate the area of the convex hull of a contact point.
- setContactDamping(float) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Alter the contact damping (native field: m_contactDamping).
- setContactErp(float) - Method in class com.jme3.bullet.SolverInfo
-
Alter the error-reduction parameter for contact constraints (native field: m_erp2).
- setContactFilterEnabled(boolean) - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Enable/disable contact filtering for this shape.
- setContactManager(ContactManager) - Method in class com.jme3.bullet.PhysicsSpace
-
Replace the current ContactManager with the specified one.
- setContactMotion1(long, float) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Alter the contact motion #1 of the specified point (native field: m_contactMotion1).
- setContactMotion2(long, float) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Alter the contact motion #2 of the specified point (native field: m_contactMotion2).
- setContactProcessingThreshold(float) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Alter the contact-processing threshold (native field: m_contactProcessingThreshold).
- setContactResponse(boolean) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Enable/disable this character's contact response.
- setContactResponse(boolean) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Enable/disable the body's contact response.
- setContactResponseSubtree(PhysicsLink, boolean) - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Alter the contact-response setting of the specified link and all its descendants (excluding released attachments).
- setContactStiffness(float) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Alter the contact stiffness (native field: m_contactStiffness).
- setConvexHullDownSampling(int) - Method in class vhacd.VHACDParameters
-
Set precision of the convex-hull generation process during the clipping plane selection stage (native field: m_convexhullDownsampling).
- setCoordinateSystem(int, int, int) - Method in class com.jme3.bullet.objects.infos.VehicleController
-
Alter the coordinate system of the vehicle.
- setCoordinateSystem(Vector3f, Vector3f, Vector3f) - Method in class com.jme3.bullet.objects.infos.VehicleController
-
Customize the coordinate system of the vehicle.
- setDamping(float) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Alter the viscous damping ratio for new rigid bodies.
- setDamping(float) - Method in class com.jme3.bullet.animation.DacLinks
-
Alter the viscous damping ratio for all rigid bodies, including new ones.
- setDamping(float) - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Alter this motor's damping (native field: m_damping).
- setDamping(float) - Method in class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
Alter this motor's damping (native field: m_damping).
- setDamping(float) - Method in class com.jme3.bullet.joints.Point2PointJoint
-
Alter the joint's damping.
- setDamping(float, float) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Alter the body's damping.
- setDamping(int, float) - Method in class com.jme3.bullet.joints.SixDofSpringJoint
-
Alter the damping for the indexed degree of freedom.
- setDamping(int, float, boolean) - Method in class com.jme3.bullet.joints.New6Dof
-
Alter the damping for the indexed degree of freedom.
- setDampingDirAng(float) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter the joint's damping for on-axis rotation between the limits.
- setDampingDirLin(float) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter the joint's damping for on-axis translation between the limits.
- setDampingLimAng(float) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter the joint's damping for on-axis rotation hitting the limits.
- setDampingLimited(boolean) - Method in class com.jme3.bullet.joints.motors.RotationMotor
-
Limit or unlimit the spring's damping (native field: m_springDampingLimited).
- setDampingLimited(int, boolean) - Method in class com.jme3.bullet.joints.motors.TranslationMotor
-
Limit or unlimit the damping of the indexed spring (m_springDampingLimited).
- setDampingLimLin(float) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter the joint's damping for on-axis translation hitting the limits.
- setDampingOrthoAng(float) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter the joint's damping for off-axis rotation.
- setDampingOrthoLin(float) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter the joint's damping for off-axis translation.
- setDeactivationDeadline(float) - Static method in class com.jme3.bullet.objects.PhysicsBody
-
Alter the global deactivation deadline.
- setDeactivationEnabled(boolean) - Static method in class com.jme3.bullet.objects.PhysicsBody
-
Alter the global deactivation enable flag.
- setDeactivationTime(float) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Alter the deactivation time (native field: m_deactivationTime).
- setDebugAngularVelocityFilter(BulletDebugAppState.DebugAppStateFilter) - Method in class com.jme3.bullet.BulletAppState
-
Alter which angular velocities are included in the debug visualization.
- setDebugAxisLength(float) - Method in class com.jme3.bullet.BulletAppState
-
Alter the length of the debug axis arrows.
- setDebugAxisLineWidth(float) - Method in class com.jme3.bullet.BulletAppState
-
Alter the line width for debug axis arrows.
- setDebugBoundingBoxFilter(BulletDebugAppState.DebugAppStateFilter) - Method in class com.jme3.bullet.BulletAppState
-
Alter which bounding boxes are included in the debug visualization.
- setDebugCamera(Camera) - Method in class com.jme3.bullet.BulletAppState
-
Replace the Camera used for debug visualization.
- setDebugClusterFilter(BulletDebugAppState.DebugAppStateFilter) - Method in class com.jme3.bullet.SoftPhysicsAppState
-
Alter which soft-body clusters are included in the debug visualization.
- setDebugEnabled(boolean) - Method in class com.jme3.bullet.BulletAppState
-
Enable or disable debug visualization.
- setDebugEnabled(boolean) - Method in class vhacd.VHACDParameters
-
Alter whether debug output is enabled.
- setDebugEnabled(boolean) - Method in class vhacd4.Vhacd4Parameters
-
Alter whether debug output is enabled.
- setDebugFilter(BulletDebugAppState.DebugAppStateFilter) - Method in class com.jme3.bullet.BulletAppState
-
Alter which objects are included in the debug visualization.
- setDebugGravityVectorFilter(BulletDebugAppState.DebugAppStateFilter) - Method in class com.jme3.bullet.BulletAppState
-
Alter which gravity vectors are included in the debug visualization.
- setDebugInitListener(DebugInitListener) - Method in class com.jme3.bullet.BulletAppState
-
Replace or remove the init listener for the BulletDebugAppState.
- setDebugJointLineWidth(float) - Method in class com.jme3.bullet.BulletAppState
-
Alter the line width for PhysicsJoint debug arrows.
- setDebugMaterial(Material) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Apply or remove a custom debug material.
- setDebugMeshInitListener(DebugMeshInitListener) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Apply or remove a listener for new debug meshes.
- setDebugMeshNormals(MeshNormals) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Alter which normals to include in new debug meshes.
- setDebugMeshNormals(MeshNormals) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Alter which normals to include in new debug meshes.
- setDebugMeshResolution(int) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Alter the mesh resolution for new debug meshes.
- setDebugNumSides(int) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Alter how many sides of this object's default debug materials are visible.
- setDebugShadowMode(RenderQueue.ShadowMode) - Method in class com.jme3.bullet.BulletAppState
-
Alter the shadow mode of the debug root node.
- setDebugSweptSphereFilter(BulletDebugAppState.DebugAppStateFilter) - Method in class com.jme3.bullet.BulletAppState
-
Alter which swept spheres are included in the debug visualization.
- setDebugVelocityVectorFilter(BulletDebugAppState.DebugAppStateFilter) - Method in class com.jme3.bullet.BulletAppState
-
Alter which velocity vectors are included in the debug visualization.
- setDebugViewPorts(ViewPort...) - Method in class com.jme3.bullet.BulletAppState
-
Alter which view ports will render the debug visualization.
- setDefaultMargin(float) - Static method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Alter the default margin for new shapes that are neither capsules nor spheres.
- setDisableForRagdoll(boolean) - Method in class com.jme3.bullet.animation.IKJoint
-
Alter whether to disable the Constraint when entering ragdoll mode.
- setDistance1(long, float) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Alter the separation distance of the specified point (native field: m_distance1).
- setDriftIterations(int) - Method in class com.jme3.bullet.objects.infos.SoftBodyConfig
-
Alter the number of drift-solver iterations (native field: diterations).
- setDucked(boolean) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Alter the character's ducking state.
- setDuckedFactor(float) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Alter the collision-shape height multiplier for ducking.
- setDynamic(Vector3f) - Method in class com.jme3.bullet.animation.BoneLink
-
Immediately put this link into dynamic mode.
- setDynamic(Vector3f) - Method in class com.jme3.bullet.animation.PhysicsLink
-
Immediately put this link into dynamic mode.
- setDynamic(Vector3f) - Method in class com.jme3.bullet.animation.TorsoLink
-
Immediately put this link into dynamic mode.
- setDynamic(Vector3f, boolean, boolean, boolean) - Method in class com.jme3.bullet.animation.BoneLink
-
Immediately put this link into dynamic mode and update the range of motion of its joint.
- setDynamic(Vector3f, Quaternion) - Method in class com.jme3.bullet.animation.BoneLink
-
Immediately put this link into dynamic mode and lock its PhysicsJoint at the specified rotation.
- setDynamicChain(PhysicsLink, int, Vector3f, boolean) - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Immediately put the specified link and all its ancestors (excluding the torso) into dynamic mode.
- setDynamicSubtree(PhysicsLink, Vector3f, boolean) - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Immediately put the specified link and all its descendants (excluding released attachments) into dynamic mode.
- setEnabled(boolean) - Method in class com.jme3.bullet.animation.IKController
-
Enable or disable this controller.
- setEnabled(boolean) - Method in class com.jme3.bullet.control.AbstractPhysicsControl
-
Enable or disable this Control.
- setEnabled(boolean) - Method in class com.jme3.bullet.control.GhostControl
-
Enable or disable this Control.
- setEnabled(boolean) - Method in interface com.jme3.bullet.control.PhysicsControl
-
Enable or disable this control.
- setEnabled(boolean) - Method in class com.jme3.bullet.control.RigidBodyControl
-
Enable or disable this Control.
- setEnabled(boolean) - Method in class com.jme3.bullet.control.VehicleControl
-
Enable or disable this Control.
- setEnabled(boolean) - Method in class com.jme3.bullet.debug.DebugConfiguration
-
Alter whether (debug) visualization is enabled.
- setEnabled(boolean) - Method in class com.jme3.bullet.joints.Constraint
-
Enable or disable this Constraint.
- setEnabled(int, boolean) - Method in class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
Enable or disable the indexed axis (native field: m_enableMotor).
- setEnabled(Control, boolean) - Static method in class jme3utilities.minie.MyControlP
-
Alter the enabled state of a scene-graph control.
- setEnabled(DumpFlags, boolean) - Method in class jme3utilities.minie.PhysicsDumper
-
Configure the specified dump flag.
- setEnableMotor(boolean) - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Enable or disable this motor (native field: m_enableMotor).
- setEnableSleep(boolean) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Alter the body's activation state to allow/disallow sleeping.
- setEndBoneTransforms(Transform[]) - Method in class com.jme3.bullet.animation.BoneLink
-
Alter the local transform for each managed bone at the end of a blend to
Reset
submode. - setEndBoneTransforms(Transform[]) - Method in class com.jme3.bullet.animation.TorsoLink
-
Alter the local transform for each managed bone at the end of a blend interval, for use with the
Reset
kinematic submode. - setEquilibriumPoint() - Method in class com.jme3.bullet.joints.New6Dof
-
Alter the equilibrium points for all degrees of freedom, based on the constraint's current location/orientation.
- setEquilibriumPoint() - Method in class com.jme3.bullet.joints.SixDofSpringJoint
-
Alter the equilibrium points for all degrees of freedom, based on the joint's current location/orientation.
- setEquilibriumPoint(int) - Method in class com.jme3.bullet.joints.New6Dof
-
Alter the equilibrium point of the indexed degree of freedom, based on the constraint's current location/orientation.
- setEquilibriumPoint(int) - Method in class com.jme3.bullet.joints.SixDofSpringJoint
-
Alter the equilibrium point of the indexed degree of freedom, based on the joint's current location/orientation.
- setEquilibriumPoint(int, float) - Method in class com.jme3.bullet.joints.New6Dof
-
Alter the equilibrium point of the indexed degree of freedom.
- setERP(float) - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Alter this motor's error-reduction parameter at the limits (native field: m_stopERP).
- setERP(float) - Method in class com.jme3.bullet.joints.SoftPhysicsJoint
-
Set the error-reduction parameter (aka ERP).
- setERP(Vector3f) - Method in class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
Alter this motor's error-reduction parameters at the limits (native field: m_stopERP).
- setEventDispatchImpulseThreshold(float) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Alter the event-dispatch impulse threshold of this control.
- setFallSpeed(float) - Method in class com.jme3.bullet.control.CharacterControl
-
Alter this character's maximum fall speed (terminal velocity).
- setFallSpeed(float) - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Alter the character's maximum fall speed (terminal velocity).
- setFallSpeed(float) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Alter this character's maximum fall speed (terminal velocity).
- setFeedback(boolean) - Method in class com.jme3.bullet.joints.Constraint
-
Enable or disable feedback for this Constraint.
- setFillMode(FillMode) - Method in class vhacd4.Vhacd4Parameters
-
Specify the algorithm that fills voxels to create a solid object (native field: m_fillMode).
- setFilter(BulletDebugAppState.DebugAppStateFilter) - Method in class com.jme3.bullet.debug.BulletDebugAppState
-
Alter which physics objects are visualized.
- setFilter(BulletDebugAppState.DebugAppStateFilter) - Method in class com.jme3.bullet.debug.DebugConfiguration
-
Alter which physics objects are included in the visualization.
- setFindBestPlane(boolean) - Method in class vhacd4.Vhacd4Parameters
-
Alter whether V-HACD should try to find the optimal location for splitting hulls (native field: m_findBestPlane).
- setFlags(long, int) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Alter the flags of the specified point (native field: m_contactPointFlags).
- setForceUpdateAllAabbs(boolean) - Method in class com.jme3.bullet.CollisionSpace
-
Alter whether the bounding boxes of inactive collision objects should be recomputed during each
update()
(native field: m_forceUpdateAllAabbs). - setFriction(float) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Alter the collision object's friction (native field: m_friction).
- setFrictionSlip(float) - Method in class com.jme3.bullet.objects.infos.VehicleTuning
-
Alter the friction between tires and ground (native field: m_frictionSlip).
- setFrictionSlip(float) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Alter the initial friction for new wheels.
- setFrictionSlip(float) - Method in class com.jme3.bullet.objects.VehicleWheel
-
Alter the friction between this wheel's tire and the ground (native field: m_frictionSlip).
- setFrictionSlip(int, float) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Alter the friction of the indexed wheel.
- setFrontWheel(boolean) - Method in class com.jme3.bullet.objects.VehicleWheel
-
Alter whether this wheel is a front (steering) wheel (native field: m_bIsFrontWheel).
- setGlobalCfm(float) - Method in class com.jme3.bullet.SolverInfo
-
Alter the global constraint-force mixing parameter (native field: m_globalCfm).
- setGravity(float) - Method in class com.jme3.bullet.control.CharacterControl
-
Alter the character's gravitational acceleration.
- setGravity(float) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Alter the character's gravitational acceleration without altering its "up" vector.
- setGravity(Vector3f) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Alter this control's gravitational acceleration for Ragdoll mode.
- setGravity(Vector3f) - Method in class com.jme3.bullet.animation.DacLinks
-
Alter this control's gravitational acceleration for Ragdoll mode.
- setGravity(Vector3f) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Alter the gravity acting on this character.
- setGravity(Vector3f) - Method in class com.jme3.bullet.DeformableSpace
-
Alter the gravitational acceleration acting on newly-added bodies.
- setGravity(Vector3f) - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Alter the character's gravitational acceleration.
- setGravity(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsBody
-
Alter this body's gravitational acceleration.
- setGravity(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Alter this character's gravitational acceleration.
- setGravity(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Alter the body's gravitational acceleration.
- setGravity(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Alter this body's gravitational acceleration.
- setGravity(Vector3f) - Method in class com.jme3.bullet.PhysicsSoftSpace
-
Alter the gravitational acceleration acting on newly-added bodies.
- setGravity(Vector3f) - Method in class com.jme3.bullet.PhysicsSpace
-
Alter the gravitational acceleration acting on newly-added bodies.
- setGravity(Vector3f) - Method in class com.jme3.bullet.SoftBodyWorldInfo
-
Alter the gravitational acceleration.
- setGravityDp(Vec3d) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Alter the body's gravitational acceleration.
- setGravityVectorFilter(BulletDebugAppState.DebugAppStateFilter) - Method in class com.jme3.bullet.debug.BulletDebugAppState
-
Alter which gravity vectors are visualized.
- setGravityVectorFilter(BulletDebugAppState.DebugAppStateFilter) - Method in class com.jme3.bullet.debug.DebugConfiguration
-
Alter which gravity vectors are included in the visualization.
- setGreenArrow(Vector3f, Vector3f) - Method in class com.jme3.bullet.debug.DebugTools
-
Alter the location and extent of the green arrow.
- setHalfExtents(CollisionShape, Vector3f) - Static method in class jme3utilities.minie.MyShape
-
Copy a shape, altering only its half extents.
- setHeight(CollisionShape, float) - Static method in class jme3utilities.minie.MyShape
-
Copy a shape, altering only its height.
- setHeightPercent(float) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Alter the height of the collision shape.
- setIgnoredHops(int) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Alter the maximum number of physics-joint hops across which bodies will ignore collisions.
- setIgnoreList(PhysicsCollisionObject[]) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Replace the ignore list.
- setImpulseClamp(float) - Method in class com.jme3.bullet.joints.Point2PointJoint
-
Alter the joint's impulse clamp.
- setIndexBuffers(boolean) - Static method in class com.jme3.bullet.util.DebugShapeFactory
-
Alter whether to index new debug meshes.
- setIndexBuffers(int) - Static method in class com.jme3.bullet.util.DebugShapeFactory
-
Alter whether to index new debug meshes.
- setInfluence(float) - Method in class com.jme3.bullet.joints.Anchor
-
Alter how much influence the anchor has on the bodies.
- setInitListener(DebugInitListener) - Method in class com.jme3.bullet.debug.DebugConfiguration
-
Replace or remove the init listener for the BulletDebugAppState.
- setInverseInertiaLocal(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Alter the principal (diagonal) components of the local inertia tensor in the body's local coordinates.
- setJoint(PhysicsJoint) - Method in class com.jme3.bullet.animation.PhysicsLink
-
Assign a physics joint to this link, or cancel the assigned joint.
- setJointErp(float) - Method in class com.jme3.bullet.SolverInfo
-
Alter the error-reduction parameter for non-contact constraints (native field: m_erp).
- setJointLimits(String, RangeOfMotion) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Alter the range of motion of the joint connecting the named BoneLink to its parent in the link hierarchy.
- setJointLimits(String, RangeOfMotion) - Method in class com.jme3.bullet.animation.DacLinks
-
Alter the range of motion of the joint connecting the named BoneLink to its parent in the link hierarchy.
- setJointLineWidth(float) - Method in class com.jme3.bullet.debug.BulletDebugAppState
-
Alter the line width for PhysicsJoint arrows.
- setJointLineWidth(float) - Method in class com.jme3.bullet.debug.DebugConfiguration
-
Alter the line width for PhysicsJoint arrows.
- setJointPosition(int, float) - Method in class com.jme3.bullet.MultiBodyLink
-
Alter the position of the indexed DOF.
- setJointVelocity(int, float) - Method in class com.jme3.bullet.MultiBodyLink
-
Alter the velocity of the indexed DOF.
- setJumpForce(Vector3f) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Alter the impulse applied at the start of each jump.
- setJumpSpeed(float) - Method in class com.jme3.bullet.control.CharacterControl
-
Alter the character's jump speed.
- setJumpSpeed(float) - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Alter the character's jump speed.
- setJumpSpeed(float) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Alter this character's jump speed.
- setKinematic(boolean) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Transition the character from kinematic mode to dynamic mode or vice versa.
- setKinematic(boolean) - Method in class com.jme3.bullet.control.JoinedBodyControl
-
Transition the body from kinematic mode to dynamic mode or vice versa.
- setKinematic(boolean) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Put the body into kinematic mode or take it out of kinematic mode.
- setKinematicMode() - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Immediately put all links into purely kinematic mode.
- setKinematicMode(KinematicSubmode) - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Immediately put all links into purely kinematic mode.
- setKinematicSpatial(boolean) - Method in class com.jme3.bullet.control.RigidBodyControl
-
Enable or disable kinematic mode for this Control.
- setLateralFrictionDir1(long, Vector3f) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Alter the lateral friction direction #1 of the specified point (native field: m_lateralFrictionDir1).
- setLateralFrictionDir2(long, Vector3f) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Alter the lateral friction direction #2 of the specified point (native field: m_lateralFrictionDir2).
- setLimit(float, float) - Method in class com.jme3.bullet.joints.HingeJoint
-
Alter the angular limits for this joint.
- setLimit(float, float, float) - Method in class com.jme3.bullet.joints.ConeJoint
-
Alter the angular limits for this joint.
- setLimit(float, float, float, float, float) - Method in class com.jme3.bullet.joints.HingeJoint
-
Alter the angular limits for this joint.
- setLimitSoftness(float) - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Alter this motor's limit softness (native field: m_limitSoftness).
- setLimitSoftness(float) - Method in class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
Alter the limit softness (native field: m_limitSoftness).
- setLinearDamping(float) - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Alter the character's linear damping.
- setLinearDamping(float) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Alter this character's linear damping.
- setLinearDamping(float) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Alter the body's linear damping.
- setLinearFactor(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Alter the body's linear factors.
- setLinearLowerLimit(Vector3f) - Method in class com.jme3.bullet.joints.SixDofJoint
-
Alter the joint's lower limits for translation of all 3 axes.
- setLinearSleepingThreshold(float) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Alter the body's linear-motion sleeping threshold.
- setLinearStiffness(float) - Method in class com.jme3.bullet.objects.infos.SoftBodyMaterial
-
Alter the linear-stiffness coefficient (native field: m_kLST).
- setLinearUpperLimit(Vector3f) - Method in class com.jme3.bullet.joints.SixDofJoint
-
Alter the joint's upper limits for translation of all 3 axes.
- setLinearVelocity(Vector3f) - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Alter the linear velocity of the character's center.
- setLinearVelocity(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Alter the linear velocity of this character's center.
- setLinearVelocity(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Alter the linear velocity of the body's center of mass.
- setLinearVelocityDp(Vec3d) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Alter the linear velocity of the body's center of mass.
- setLocalPointA(long, Vector3f) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Alter the location of the specified point in the local coordinates of object A (native name: m_localPointA).
- setLocalPointB(long, Vector3f) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Alter the location of the specified point in the local coordinates of object B (native name: m_localPointB).
- setLocalThreadPhysicsSpace(CollisionSpace) - Static method in class com.jme3.bullet.CollisionSpace
-
Alter the CollisionSpace associated with this thread.
- setLocalTransform(int, Transform) - Method in class com.jme3.bullet.animation.BoneLink
-
Alter the local transform of the indexed managed bone.
- setLocalTransform(int, Transform) - Method in class com.jme3.bullet.animation.TorsoLink
-
Alter the local transform of the indexed managed bone.
- setLocation(Vector3f) - Method in class com.jme3.bullet.joints.SoftLinearJoint
-
Alter the joint location.
- setLocationAndBasis(Vector3f, Matrix3f) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Directly alter the collision object's location and basis.
- setLowerAngLimit(float) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter the joint's lower limit for on-axis rotation.
- setLowerLimit(float) - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Alter this motor's constraint lower limit (native field: m_loLimit).
- setLowerLimit(float) - Method in class com.jme3.bullet.joints.NewHinge
-
Alter the lower limit for axis1 rotation.
- setLowerLimit(Vector3f) - Method in class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
Alter this motor's constraint lower limits (native field: m_lowerLimit).
- setLowerLinLimit(float) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter the joint's lower limit for on-axis translation.
- setMagentaArrow(Vector3f, Vector3f) - Method in class com.jme3.bullet.debug.DebugTools
-
Alter the location and extent of the magenta arrow.
- setMainBoneName(String) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Specify the main bone.
- setMainBoneName(String) - Method in class com.jme3.bullet.animation.DacLinks
-
Specify the main bone.
- setMargin(float) - Method in class com.jme3.bullet.collision.shapes.CapsuleCollisionShape
-
Alter the collision margin of the shape.
- setMargin(float) - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Alter the collision margin of this shape.
- setMargin(float) - Method in class com.jme3.bullet.collision.shapes.MinkowskiSum
-
Alter the collision margin of this shape.
- setMargin(float) - Method in class com.jme3.bullet.collision.shapes.SphereCollisionShape
-
Alter the collision margin of this shape.
- setMargin(float) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Alter the collision margin of this body.
- setMass(float) - Method in class com.jme3.bullet.objects.PhysicsBody
-
Alter this body's total mass.
- setMass(float) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Alter the body's mass.
- setMass(float) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Alter the total mass for this body, distributing it in proportion to the current mass of each node.
- setMass(PhysicsLink, float) - Method in class com.jme3.bullet.animation.DacLinks
-
Alter the mass of the specified link.
- setMass(String, float) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Alter the mass of the named bone/torso.
- setMass(String, float) - Method in class com.jme3.bullet.animation.DacLinks
-
Alter the mass of the named bone/torso.
- setMassByArea(float) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Alter the total mass for this body, distributing it based on the area of each face.
- setMassByCurrent(float) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Alter the total mass for this body, distributing it to nodes in proportion to their current masses.
- setMasses(FloatBuffer) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Alter the masses of all nodes.
- setMassFromDensity(float) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Alter the total mass of this body, weighted by volume.
- setMaxAngMotorForce(float) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter the maximum force of the rotation motor.
- setMaxConcavity(double) - Method in class vhacd.VHACDParameters
-
Set maximum concavity (native field: m_concavity).
- setMaxDisplacement(float) - Method in class com.jme3.bullet.SoftBodyWorldInfo
-
Alter the maximum distance a node can travel per simulation step.
- setMaxHulls(int) - Method in class vhacd4.Vhacd4Parameters
-
Alter the maximum number of convex hulls (native field: m_maxConvexHulls).
- setMaxLimitForce(float) - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Alter the limit maximum force (native field: m_maxLimitForce).
- setMaxLinMotorForce(float) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter the maximum force of the translation motor.
- setMaxMotorForce(float) - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Alter this motor's maximum force (native field: m_maxMotorForce).
- setMaxMotorForce(Vector3f) - Method in class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
Alter this motor's maximum forces (native field: m_maxMotorForce).
- setMaxPenetrationDepth(float) - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Alter the character's maximum penetration depth.
- setMaxPenetrationDepth(float) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Alter this character's maximum penetration depth.
- setMaxRecursion(int) - Method in class vhacd4.Vhacd4Parameters
-
Alter the maximum recursion depth (native field: m_maxRecursionDepth).
- setMaxSlope(float) - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Alter the character's maximum slope angle.
- setMaxSlope(float) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Alter this character's maximum slope angle.
- setMaxSubSteps(int) - Method in class com.jme3.bullet.PhysicsSpace
-
Alter the maximum number of simulation steps per frame.
- setMaxSuspensionForce(float) - Method in class com.jme3.bullet.objects.infos.VehicleTuning
-
Alter the force exerted by each wheel's suspension (native field: m_maxSuspensionForce).
- setMaxSuspensionForce(float) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Alter the initial maximum suspension force for new wheels.
- setMaxSuspensionForce(float) - Method in class com.jme3.bullet.objects.VehicleWheel
-
Alter the maximum force exerted by this wheel's suspension (native field: m_maxSuspensionForce).
- setMaxSuspensionForce(int, float) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Alter the maximum suspension force for the specified wheel.
- setMaxSuspensionTravelCm(float) - Method in class com.jme3.bullet.objects.infos.VehicleTuning
-
Alter the maximum travel distance for the suspension (native field: m_maxSuspensionTravelCm).
- setMaxSuspensionTravelCm(float) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Alter the initial maximum suspension travel distance for new wheels.
- setMaxSuspensionTravelCm(float) - Method in class com.jme3.bullet.objects.VehicleWheel
-
Alter the maximum travel distance for this wheel's suspension (native field: m_maxSuspensionTravelCm).
- setMaxSuspensionTravelCm(int, float) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Alter the maximum suspension travel distance for the indexed wheel.
- setMaxTimeStep(float) - Method in class com.jme3.bullet.PhysicsSpace
-
Alter the maximum time step (imposed when maxSubSteps=0).
- setMaxVerticesPerHull(int) - Method in class vhacd.VHACDParameters
-
Alter the maximum number of vertices per convex hull (native field: m_maxNumVerticesPerCH).
- setMaxVerticesPerHull(int) - Method in class vhacd4.Vhacd4Parameters
-
Alter the maximum number of vertices per convex hull (native field: m_maxNumVerticesPerCH).
- setMinBatch(int) - Method in class com.jme3.bullet.SolverInfo
-
Alter the minimum batch size (native field: m_minimumSolverBatchSize).
- setMinEdgeLength(int) - Method in class vhacd4.Vhacd4Parameters
-
Alter the minimum edge length (native field: m_minEdgeLength).
- setMinVolumePerHull(double) - Method in class vhacd.VHACDParameters
-
Set the minimum volume to add vertices to convex hulls (native field: m_minVolumePerCH).
- setMode(int) - Method in class com.jme3.bullet.SolverInfo
-
Alter the mode flags (native field: m_solverMode).
- setMotorEnabled(boolean) - Method in class com.jme3.bullet.joints.motors.RotationMotor
-
Enable or disable this motor (native field: m_enableMotor).
- setMotorEnabled(int, boolean) - Method in class com.jme3.bullet.joints.motors.TranslationMotor
-
Enable or disable the indexed axis (m_enableMotor).
- setNativeId(long) - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Initialize the native ID.
- setNativeId(long) - Method in class com.jme3.bullet.joints.PhysicsJoint
-
Initialize the native ID.
- setNativeId(long) - Method in class com.jme3.bullet.NativePhysicsObject
-
Assign a tracked native object to this instance, assuming that no native object is assigned.
- setNativeIdNotTracked(long) - Method in class com.jme3.bullet.NativePhysicsObject
-
Assign an untracked native object to this instance, assuming that no native object is assigned.
- setNodeMass(int, float) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Alter the mass of the indexed node.
- setNodeVelocity(int, Vector3f) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Alter the velocity of the indexed node.
- setNormalCFM(float) - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Alter this motor's constraint-force mixing parameter for normal conditions (native field: m_normalCFM).
- setNormalCFM(Vector3f) - Method in class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
Alter this motor's constraint-force mixing parameters for normal conditions (native field: m_normalCFM).
- setNormals(FloatBuffer) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Alter the normal vectors of all nodes.
- setNormalWorldOnB(long, Vector3f) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Alter the normal on object B of the specified point in physics-space coordinates (native name: m_normalWorldOnB).
- setNumIterations(int) - Method in class com.jme3.bullet.SolverInfo
-
Alter the number of iterations (native field: m_numIterations).
- setNumSolvers(int) - Method in class com.jme3.bullet.BulletAppState
-
Alter the number of solvers in the thread-safe pool.
- setParent(PhysicsLink) - Method in class com.jme3.bullet.animation.PhysicsLink
-
Assign the parent/manager for this link.
- setPCA(boolean) - Method in class vhacd.VHACDParameters
-
Enable/disable normalizing the mesh before applying the convex decomposition (native field: m_pca).
- setPhysicsDamping(float) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Alter the damping factor for horizontal motion.
- setPhysicsLocation(Vector3f) - Method in class com.jme3.bullet.animation.DacLinks
-
Translate the torso to the specified location.
- setPhysicsLocation(Vector3f) - Method in class com.jme3.bullet.control.AbstractPhysicsControl
-
Translate the physics object to the specified location.
- setPhysicsLocation(Vector3f) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Translate the character instantly to the specified location.
- setPhysicsLocation(Vector3f) - Method in class com.jme3.bullet.control.CharacterControl
-
Translate the PhysicsCharacter to the specified location.
- setPhysicsLocation(Vector3f) - Method in class com.jme3.bullet.control.JoinedBodyControl
-
Translate the body instantly to the specified location.
- setPhysicsLocation(Vector3f) - Method in class com.jme3.bullet.control.SoftBodyControl
-
Translate the soft body to the specified location.
- setPhysicsLocation(Vector3f) - Method in class com.jme3.bullet.objects.MultiBodyCollider
-
Directly alter the location of this collider's center.
- setPhysicsLocation(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsBody
-
Directly relocate this body's center.
- setPhysicsLocation(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Directly alter this character's location.
- setPhysicsLocation(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsGhostObject
-
Directly alter the location of the ghost's center.
- setPhysicsLocation(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Directly relocate the body's center of mass.
- setPhysicsLocation(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Directly relocate the center of this body's bounding box.
- setPhysicsLocationDp(Vec3d) - Method in class com.jme3.bullet.objects.MultiBodyCollider
-
Directly alter the location of this collider's center.
- setPhysicsLocationDp(Vec3d) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Directly alter this character's location.
- setPhysicsLocationDp(Vec3d) - Method in class com.jme3.bullet.objects.PhysicsGhostObject
-
Directly alter the location of the ghost's center.
- setPhysicsLocationDp(Vec3d) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Directly relocate the body's center of mass.
- setPhysicsLocationDp(Vec3d) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Directly relocate the center of this body's bounding box.
- setPhysicsRotation(Matrix3f) - Method in class com.jme3.bullet.objects.MultiBodyCollider
-
Directly alter this collider's orientation.
- setPhysicsRotation(Matrix3f) - Method in class com.jme3.bullet.objects.PhysicsGhostObject
-
Directly alter the ghost's orientation.
- setPhysicsRotation(Matrix3f) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Directly alter the body's orientation.
- setPhysicsRotation(Quaternion) - Method in class com.jme3.bullet.animation.DacLinks
-
Rotate the torso to the specified orientation.
- setPhysicsRotation(Quaternion) - Method in class com.jme3.bullet.control.AbstractPhysicsControl
-
Rotate the physics object to the specified orientation.
- setPhysicsRotation(Quaternion) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Rotate the character's viewpoint to the specified orientation.
- setPhysicsRotation(Quaternion) - Method in class com.jme3.bullet.control.CharacterControl
-
Rotate the PhysicsCharacter to the specified orientation.
- setPhysicsRotation(Quaternion) - Method in class com.jme3.bullet.control.JoinedBodyControl
-
Rotate the body instantly to the specified orientation.
- setPhysicsRotation(Quaternion) - Method in class com.jme3.bullet.control.SoftBodyControl
-
Rotate the soft body to the specified orientation.
- setPhysicsRotation(Quaternion) - Method in class com.jme3.bullet.objects.PhysicsGhostObject
-
Directly alter the ghost's orientation.
- setPhysicsRotation(Quaternion) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Directly reorient the body.
- setPhysicsRotationDp(Matrix3d) - Method in class com.jme3.bullet.objects.MultiBodyCollider
-
Directly alter this collider's orientation.
- setPhysicsRotationDp(Matrix3d) - Method in class com.jme3.bullet.objects.PhysicsGhostObject
-
Directly alter the ghost's orientation.
- setPhysicsRotationDp(Matrix3d) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Directly reorient the body.
- setPhysicsRotationDp(Quatd) - Method in class com.jme3.bullet.objects.PhysicsGhostObject
-
Directly alter the ghost's orientation.
- setPhysicsRotationDp(Quatd) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Directly reorient the body.
- setPhysicsScale(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Rescale the body.
- setPhysicsSpace(PhysicsSpace) - Method in class com.jme3.bullet.BulletAppState
-
Alter which PhysicsSpace is managed by this state.
- setPhysicsSpace(PhysicsSpace) - Method in class com.jme3.bullet.control.AbstractPhysicsControl
-
If enabled, add this control's physics objects to the specified PhysicsSpace.
- setPhysicsSpace(PhysicsSpace) - Method in class com.jme3.bullet.control.GhostControl
-
If enabled, add this control's physics object to the specified PhysicsSpace.
- setPhysicsSpace(PhysicsSpace) - Method in interface com.jme3.bullet.control.PhysicsControl
-
If this control is enabled, add its physics objects to the specified PhysicsSpace.
- setPhysicsSpace(PhysicsSpace) - Method in class com.jme3.bullet.control.RigidBodyControl
-
If enabled, add this control's body to the specified PhysicsSpace.
- setPhysicsSpace(PhysicsSpace) - Method in class com.jme3.bullet.control.SoftBodyControl
-
If enabled, add this control's physics object to the specified PhysicsSpace.
- setPhysicsSpace(PhysicsSpace) - Method in class com.jme3.bullet.control.VehicleControl
-
If enabled, add this control's physics object to the specified PhysicsSpace.
- setPhysicsSpace(PhysicsSpace) - Method in class com.jme3.bullet.joints.PhysicsJoint
-
Alter which PhysicsSpace this joint is added to.
- setPhysicsTransform(Transform) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Directly alter the body's transform, including the scale of its shape.
- setPinkArrow(Vector3f, Vector3f) - Method in class com.jme3.bullet.debug.DebugTools
-
Alter the location and extent of the pink arrow.
- setPivotInA(Vector3f) - Method in class com.jme3.bullet.joints.Constraint
-
Alter the pivot location in A's scaled local coordinates.
- setPivotInA(Vector3f) - Method in class com.jme3.bullet.joints.Point2PointJoint
-
Alter the pivot location in A's scaled local coordinates.
- setPivotInB(Vector3f) - Method in class com.jme3.bullet.joints.Anchor
-
Alter the pivot location in B's local coordinates.
- setPivotInB(Vector3f) - Method in class com.jme3.bullet.joints.Constraint
-
Alter the pivot location in B's scaled local coordinates.
- setPivotInB(Vector3f) - Method in class com.jme3.bullet.joints.Point2PointJoint
-
Alter the pivot location in B's scaled local coordinates.
- setPlaneDownSampling(int) - Method in class vhacd.VHACDParameters
-
Set granularity of the search for the "best" clipping plane (native field: m_planeDownsampling).
- setPose(boolean, boolean) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Set the "default pose" (lowest energy state) of this body based on its current pose.
- setPositionIterations(int) - Method in class com.jme3.bullet.objects.infos.SoftBodyConfig
-
Alter the number of position-solver iterations (native field: piterations).
- setPositionWorldOnA(long, Vector3f) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Alter the location of the specified point on object A in physics-space coordinates (native field: m_positionWorldOnA).
- setPositionWorldOnB(long, Vector3f) - Static method in class com.jme3.bullet.collision.ManifoldPoints
-
Alter the location of the specified point on object B in physics-space coordinates (native field: m_positionWorldOnB).
- setPoweredAngMotor(boolean) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter whether the rotation motor is powered.
- setPoweredLinMotor(boolean) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter whether the translation motor is powered.
- setProtectGravity(boolean) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Alter whether the body's gravity should be overwritten if the body gets added to a PhysicsSpace or the gravity of the PhysicsSpace changes.
- setProtectWorldInfo(boolean) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Alter whether this body's world info should be replaced when the body gets added to a space.
- setRadius(float) - Method in class com.jme3.bullet.objects.VehicleWheel
-
Alter the radius of this wheel (native field: m_wheelsRadius).
- setRadius(CollisionShape, float) - Static method in class jme3utilities.minie.MyShape
-
Copy a shape, altering only its radius.
- setRagdollMode() - Method in class com.jme3.bullet.animation.AttachmentLink
-
Immediately put this link into ragdoll mode.
- setRagdollMode() - Method in class com.jme3.bullet.animation.BoneLink
-
Immediately put this link into ragdoll mode.
- setRagdollMode() - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Immediately put all links and IK joints into ragdoll mode.
- setRagdollMode() - Method in class com.jme3.bullet.animation.IKController
-
Immediately put this controller into ragdoll mode.
- setRagdollMode() - Method in class com.jme3.bullet.animation.PhysicsLink
-
Immediately put this link (and all its controllers) into ragdoll mode.
- setRagdollMode() - Method in class com.jme3.bullet.animation.TorsoLink
-
Immediately put this link into ragdoll mode.
- setRatio(float) - Method in class com.jme3.bullet.joints.GearJoint
-
Alter the joint's gear ratio.
- setRayTestFlags(int) - Method in class com.jme3.bullet.CollisionSpace
-
Alter the flags used in ray tests (native field: m_flags).
- setRedArrow(Vector3f, Vector3f) - Method in class com.jme3.bullet.debug.DebugTools
-
Alter the location and extent of the red arrow.
- setReinitializationCallbackEnabled(boolean) - Static method in class com.jme3.bullet.util.NativeLibrary
-
Alter whether the native library should invoke the reinitialization() callback.
- setRelativeTolerance(float) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Alter the relative tolerance for comparing scale factors.
- setRestingLengthScale(float) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Alter the scale factor for resting lengths.
- setRestitution(float) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Alter the collision object's restitution (bounciness) (native field: m_restitution).
- setRestitution(float) - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Alter this motor's restitution at the limits (native field: m_bounce).
- setRestitution(float) - Method in class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
Alter this motor's restitution at the limits (native field: m_restitution).
- setRestitutionDirAng(float) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter the joint's restitution for on-axis rotation between the limits.
- setRestitutionDirLin(float) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter the joint's restitution for on-axis translation between the limits.
- setRestitutionLimAng(float) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter the joint's restitution for on-axis rotation hitting the limits.
- setRestitutionLimLin(float) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter the joint's restitution for on-axis translation hitting the limits.
- setRestitutionOrthoAng(float) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter the joint's restitution for off-axis rotation.
- setRestitutionOrthoLin(float) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter the joint's restitution for off-axis translation.
- setRestLength(float) - Method in class com.jme3.bullet.objects.VehicleWheel
-
Alter the rest length of the suspension of this wheel (native field: m_suspensionRestLength1).
- setRigidBody(PhysicsRigidBody) - Method in class com.jme3.bullet.animation.PhysicsLink
-
Replace the rigid body for this link.
- setRollInfluence(float) - Method in class com.jme3.bullet.objects.VehicleWheel
-
Alter this wheel's roll influence (native field: m_rollInfluence).
- setRollInfluence(int, float) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Alter the roll influence of the indexed wheel.
- setRollingFriction(float) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Alter this object's rolling friction: torsional friction orthogonal to the contact normal (native field: m_rollingFriction).
- setRotationAngle(float) - Method in class com.jme3.bullet.objects.VehicleWheel
-
Alter the total rotation of this wheel (native field: m_rotation).
- setRotationOrder(RotationOrder) - Method in class com.jme3.bullet.joints.New6Dof
-
Alter the order in which to apply axis rotations.
- setRunning(boolean) - Method in class com.jme3.bullet.BulletAppState
-
Alter whether the physics simulation is running (started but not yet stopped).
- setScale(float) - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Alter the scale of this shape to a uniform factor.
- setScale(Vector3f) - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Alter the scale of this shape.
- setScale(Vector3f) - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Alter the scale of this shape and its children.
- setScale(Vector3f) - Method in class com.jme3.bullet.collision.shapes.Convex2dShape
-
Alter the scale of this shape and its base.
- setScale(Vector3f) - Method in class com.jme3.bullet.collision.shapes.GImpactCollisionShape
-
Alter the scale factors of this shape.
- setScale(Vector3f) - Method in class com.jme3.bullet.collision.shapes.infos.CompoundMesh
-
Alter the scale factors.
- setScale(Vector3f) - Method in class com.jme3.bullet.collision.shapes.MeshCollisionShape
-
Alter the scale of this shape.
- setScaledInertia(float, float, float) - Method in class com.jme3.bullet.collision.shapes.CustomConvexShape
-
Alter the scaled rotational inertia.
- setSerializingBvh(boolean) - Static method in class com.jme3.bullet.collision.shapes.MeshCollisionShape
-
Alter whether bounding-value hierarchies will be included when serializing mesh collision shapes.
- setServoEnabled(boolean) - Method in class com.jme3.bullet.joints.motors.RotationMotor
-
Enable or disable the servo (native field: m_servoMotor).
- setServoEnabled(int, boolean) - Method in class com.jme3.bullet.joints.motors.TranslationMotor
-
Enable or disable the indexed servo (m_servoMotor).
- setShadowMode(RenderQueue.ShadowMode) - Method in class com.jme3.bullet.debug.DebugConfiguration
-
Alter the shadow mode for the (debug) root node.
- setShape(CollisionShape) - Method in class com.jme3.bullet.debug.BulletCharacterDebugControl
-
Replace the lastShape and update related fields.
- setShrinkWrap(boolean) - Method in class vhacd4.Vhacd4Parameters
-
Alter whether to shrinkwrap voxel positions to the source mesh (native field: m_shrinkWrap).
- setSleepingThresholds(float, float) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Alter the body's sleeping thresholds.
- setSoftnessDirAng(float) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter the joint's softness for on-axis rotation between the limits.
- setSoftnessDirLin(float) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter the joint's softness for on-axis translation between the limits.
- setSoftnessLimAng(float) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter the joint's softness for on-axis rotation hitting the limits.
- setSoftnessLimLin(float) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter the joint's softness for on-axis translation hitting the limits.
- setSoftnessOrthoAng(float) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter the joint's softness for off-axis rotation.
- setSoftnessOrthoLin(float) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter the joint's softness for off-axis translation.
- setSolverNumIterations(int) - Method in class com.jme3.bullet.PhysicsSpace
-
Alter the number of iterations used by the contact-and-constraint solver, for compatibility with the jme3-jbullet library.
- setSolverType(SolverType) - Method in class com.jme3.bullet.BulletAppState
-
Alter which constraint solver the PhysicsSpace will use.
- setSpace(PhysicsSpace) - Method in class com.jme3.bullet.debug.DebugConfiguration
-
Alter which PhysicsSpace will be visualized.
- setSpatial(Spatial) - Method in class com.jme3.bullet.control.AbstractPhysicsControl
-
Alter which Spatial is controlled.
- setSpatial(Spatial) - Method in class com.jme3.bullet.control.GhostControl
-
Alter which Spatial is controlled.
- setSpatial(Spatial) - Method in class com.jme3.bullet.control.RigidBodyControl
-
Alter which Spatial is controlled.
- setSpatial(Spatial) - Method in class com.jme3.bullet.control.VehicleControl
-
Alter which Spatial is controlled.
- setSpatial(Spatial) - Method in class com.jme3.bullet.debug.BulletVehicleDebugControl
-
Alter which Spatial is controlled.
- setSpatial(Spatial) - Method in class com.jme3.bullet.debug.BulletCharacterDebugControl
-
Alter which Spatial is controlled.
- setSpeed(float) - Method in class com.jme3.bullet.BulletAppState
-
Alter the physics simulation speed.
- setSpinningFriction(float) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Alter this object's spinning friction: torsional friction around the contact normal (native field: m_spinningFriction).
- setSplit(float) - Method in class com.jme3.bullet.joints.SoftPhysicsJoint
-
Alter the split.
- setSplitImpulseEnabled(boolean) - Method in class com.jme3.bullet.SolverInfo
-
Alter whether split impulse is enabled globally (native field: m_splitImpulse).
- setSplitImpulseErp(float) - Method in class com.jme3.bullet.SolverInfo
-
Alter the error-reduction parameter (ERP) used with split impulse (native field: m_splitImpulseTurnErp).
- setSplitImpulseThreshold(float) - Method in class com.jme3.bullet.SolverInfo
-
Alter the degree of penetration at which split impulse will be used.
- setSpringEnabled(boolean) - Method in class com.jme3.bullet.joints.motors.RotationMotor
-
Enable or disable the spring (native field: m_enableSpring).
- setSpringEnabled(int, boolean) - Method in class com.jme3.bullet.joints.motors.TranslationMotor
-
Enable or disable the indexed spring (m_enableSpring).
- setStartupMessageEnabled(boolean) - Static method in class com.jme3.bullet.util.NativeLibrary
-
Alter whether the native library will print its startup message during initialization.
- setStepHeight(float) - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Alter the character's step height.
- setStepHeight(float) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Alter this character's step height.
- setStiffness(int, float) - Method in class com.jme3.bullet.joints.SixDofSpringJoint
-
Alter the spring stiffness for the indexed degree of freedom.
- setStiffness(int, float, boolean) - Method in class com.jme3.bullet.joints.New6Dof
-
Alter the spring stiffness for the indexed degree of freedom.
- setStiffnessLimited(boolean) - Method in class com.jme3.bullet.joints.motors.RotationMotor
-
Limit or unlimit the spring's stiffness (native field: m_springStiffnessLimited).
- setStiffnessLimited(int, boolean) - Method in class com.jme3.bullet.joints.motors.TranslationMotor
-
Limit or unlimit the stiffness of the indexed spring (m_springStiffnessLimited).
- setStopCFM(float) - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Alter this motor's constraint-force mixing parameter at the limits (native field: m_stopCFM).
- setStopCFM(Vector3f) - Method in class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
Alter this motor's constraint-force mixing parameters at the limits (native field: m_stopCFM).
- setSuspensionCompression(float) - Method in class com.jme3.bullet.objects.infos.VehicleTuning
-
Alter the suspension damping when compressed (native field: m_suspensionCompression).
- setSuspensionCompression(float) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Alter the initial damping (when the suspension is compressed) for new wheels.
- setSuspensionCompression(int, float) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Alter the damping (when the suspension is compressed) for the indexed wheel.
- setSuspensionDamping(float) - Method in class com.jme3.bullet.objects.infos.VehicleTuning
-
Alter the suspension damping when expanded (native field: m_suspensionDamping).
- setSuspensionDamping(float) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Alter the initial damping (when the suspension is expanded) for new wheels.
- setSuspensionDamping(int, float) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Alter the damping (when the suspension is expanded) for the indexed wheel.
- setSuspensionLength(float) - Method in class com.jme3.bullet.objects.VehicleWheel
-
Alter the length of this wheel's suspension (native field: m_suspensionLength).
- setSuspensionStiffness(float) - Method in class com.jme3.bullet.objects.infos.VehicleTuning
-
Alter the stiffness of the suspension (native field: m_suspensionStiffness).
- setSuspensionStiffness(float) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Alter the initial suspension stiffness for new wheels.
- setSuspensionStiffness(float) - Method in class com.jme3.bullet.objects.VehicleWheel
-
Alter the stiffness of this wheel's suspension (native field: m_suspensionStiffness).
- setSuspensionStiffness(int, float) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Alter the suspension stiffness of the indexed wheel.
- setSweepTest(boolean) - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Alter which convex-sweep test is used.
- setSweepTest(boolean) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Alter which convex-sweep test is used.
- setSweptSphereFilter(BulletDebugAppState.DebugAppStateFilter) - Method in class com.jme3.bullet.debug.BulletDebugAppState
-
Alter which swept spheres are visualized.
- setSweptSphereFilter(BulletDebugAppState.DebugAppStateFilter) - Method in class com.jme3.bullet.debug.DebugConfiguration
-
Alter which swept spheres are included in the visualization.
- setTargetAngMotorVelocity(float) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter the velocity target of the rotation motor.
- setTargetLinMotorVelocity(float) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter the velocity target of the translation motor.
- setTargetVelocity(float) - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Alter this motor's target velocity (native field: m_targetVelocity).
- setTargetVelocity(Vector3f) - Method in class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
Alter this motor's target velocity (native field: m_targetVelocity).
- setTau(float) - Method in class com.jme3.bullet.joints.Point2PointJoint
-
Alter the joint's tau value.
- setThreadingType(BulletAppState.ThreadingType) - Method in class com.jme3.bullet.BulletAppState
-
Alter which type of threading this app state uses.
- setTransform(Vector3f, Matrix3f) - Method in class com.jme3.bullet.collision.shapes.infos.ChildCollisionShape
-
Alter the child's coordinate transform copy.
- setTransformSpatial(Spatial) - Method in class com.jme3.bullet.BulletAppState
-
Alter the conversion from physics-space coordinates to world coordinates.
- setTransformSpatial(Spatial) - Method in class com.jme3.bullet.debug.DebugConfiguration
-
Alter the conversion from physics-space coordinates to world coordinates.
- setTraversalMode(int) - Method in class com.jme3.bullet.collision.shapes.infos.BoundingValueHierarchy
-
Alter the traversal mode (native field: m_traversalMode).
- setup(PhysicsJoint, boolean, boolean, boolean) - Method in class com.jme3.bullet.animation.RangeOfMotion
-
Apply this preset to the specified constraint, locking the specified rotational axes at their current angles.
- setUp(Vector3f) - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Alter the character's "up" direction.
- setUp(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Alter this character's "up" direction.
- setupDebugNode() - Method in class com.jme3.bullet.debug.DebugTools
-
Attach all the debug geometries to the debug node.
- setupJoint(SixDofJoint, boolean, boolean, boolean) - Method in class com.jme3.bullet.animation.RangeOfMotion
-
Apply this preset to the specified joint, locking the specified rotational axes at their current angles.
- setupMaterials() - Method in class com.jme3.bullet.debug.DebugTools
-
Initialize all the DebugTools materials.
- setupMaterials(AssetManager) - Method in class com.jme3.bullet.debug.BulletDebugAppState
-
Initialize the wireframe materials and child materials.
- setupMaterials(AssetManager) - Method in class com.jme3.bullet.debug.SoftDebugAppState
-
Initialize the materials.
- setupNew6Dof(New6Dof, boolean, boolean, boolean) - Method in class com.jme3.bullet.animation.RangeOfMotion
-
Apply this preset to the specified constraint, locking the specified rotational axes at their current angles.
- setUpperAngLimit(float) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter the joint's upper limit for on-axis rotation.
- setUpperLimit(float) - Method in class com.jme3.bullet.joints.motors.RotationalLimitMotor
-
Alter this motor's constraint upper limit (native field: m_hiLimit).
- setUpperLimit(float) - Method in class com.jme3.bullet.joints.NewHinge
-
Alter the upper limit for axis1 rotation.
- setUpperLimit(Vector3f) - Method in class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
Alter this motor's constraint upper limits (native field: m_upperLimit).
- setUpperLinLimit(float) - Method in class com.jme3.bullet.joints.SliderJoint
-
Alter the joint's upper limit for on-axis translation.
- setUserIndex(int) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Alter the collision object's primary user index.
- setUserIndex(int) - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Alter the primary user index.
- setUserIndex(int) - Method in class com.jme3.bullet.MultiBody
-
Alter the primary user index.
- setUserIndex2(int) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Alter the collision object's secondary user index.
- setUserIndex2(int) - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Alter the secondary user index.
- setUserIndex2(int) - Method in class com.jme3.bullet.MultiBody
-
Alter the secondary user index.
- setUserIndex3(int) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Alter the collision object's tertiary user index.
- setUserObject(Object) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Associate a "user" with the collision object.
- setVehicle(PhysicsVehicle) - Method in class com.jme3.bullet.objects.infos.RigidBodyMotionState
-
Alter which vehicle uses this motion state.
- setVehicleId(long, int) - Method in class com.jme3.bullet.objects.VehicleWheel
-
Assign this wheel to a vehicle.
- setVelocities(FloatBuffer) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Alter the velocities of all nodes.
- setVelocity(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Alter the velocities of all nodes to make them identical.
- setVelocityIterations(int) - Method in class com.jme3.bullet.objects.infos.SoftBodyConfig
-
Alter the number of velocity-solver iterations (native field: viterations).
- setVelocityVectorFilter(BulletDebugAppState.DebugAppStateFilter) - Method in class com.jme3.bullet.debug.BulletDebugAppState
-
Alter which velocity vectors are visualized.
- setVelocityVectorFilter(BulletDebugAppState.DebugAppStateFilter) - Method in class com.jme3.bullet.debug.DebugConfiguration
-
Alter which velocity vectors are included in the visualization.
- setViewDirection(Vector3f) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Alter the character's view direction, provided it's in dynamic mode.
- setViewDirection(Vector3f) - Method in class com.jme3.bullet.control.CharacterControl
-
Alter the view direction.
- setViewPorts(ViewPort...) - Method in class com.jme3.bullet.debug.DebugConfiguration
-
Alter which view ports will render the visualization.
- setVolumeDensity(float) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Set volume density (using tetrahedra) TODO clarify semantics
- setVolumeMass(float) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Set volume mass (using tetrahedra) TODO clarify semantics
- setVolumePercentError(double) - Method in class vhacd4.Vhacd4Parameters
-
Alter the tolerance for the percent difference between the voxel volume and the volume of the hull (native field: m_minimumVolumePercentErrorAllowed).
- setVolumeStiffness(float) - Method in class com.jme3.bullet.objects.infos.SoftBodyMaterial
-
Alter the volume-stiffness coefficient (native field: m_kVST).
- setVoxelResolution(int) - Method in class vhacd.VHACDParameters
-
Alter the maximum number of voxels generated during the voxelization stage (native field: m_resolution).
- setVoxelResolution(int) - Method in class vhacd4.Vhacd4Parameters
-
Alter the maximum number of voxels generated during the voxelization stage (native field: m_resolution).
- setWalkDirection(Vector3f) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Alter the character's walk velocity.
- setWalkDirection(Vector3f) - Method in class com.jme3.bullet.control.CharacterControl
-
Alter the character's walk offset.
- setWalkDirection(Vector3f) - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Alter the character's walk offset.
- setWalkDirection(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Alter this character's walk offset.
- setWaterDensity(float) - Method in class com.jme3.bullet.SoftBodyWorldInfo
-
Alter the water density.
- setWaterNormal(Vector3f) - Method in class com.jme3.bullet.SoftBodyWorldInfo
-
Alter the water normal.
- setWaterOffset(float) - Method in class com.jme3.bullet.SoftBodyWorldInfo
-
Alter the water offset.
- setWheelsDampingCompression(float) - Method in class com.jme3.bullet.objects.VehicleWheel
-
Alter this wheel's damping when the suspension is compressed (native field: m_wheelsDampingCompression).
- setWheelsDampingRelaxation(float) - Method in class com.jme3.bullet.objects.VehicleWheel
-
Alter this wheel's damping when the suspension is expanded (native field: m_wheelsDampingRelaxation).
- setWheelSpatial(Spatial) - Method in class com.jme3.bullet.objects.VehicleWheel
-
Alter which scene-graph subtree is used to visualize this wheel.
- setWindVelocity(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Alter the wind velocity.
- setWindVelocityFilter(BulletDebugAppState.DebugAppStateFilter) - Method in class com.jme3.bullet.debug.SoftDebugAppState
-
Alter which wind velocities are included in the debug visualization.
- setWindVelocityFilter(BulletDebugAppState.DebugAppStateFilter) - Method in class com.jme3.bullet.SoftPhysicsAppState
-
Alter which wind velocities are included in the debug visualization.
- setWorldInfo(SoftBodyWorldInfo) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Replace the world info of this body.
- setWorldMax(Vector3f) - Method in class com.jme3.bullet.BulletAppState
-
Alter the coordinate range.
- setWorldMin(Vector3f) - Method in class com.jme3.bullet.BulletAppState
-
Alter the coordinate range.
- setYellowArrow(Vector3f, Vector3f) - Method in class com.jme3.bullet.debug.DebugTools
-
Alter the location and extent of the yellow arrow.
- ShadowModes - Enum constant in enum class jme3utilities.minie.DumpFlags
-
shadow modes in spatials
- shapeHeuristic() - Method in class com.jme3.bullet.animation.LinkConfig
-
Read which shape heuristic to use.
- ShapeHeuristic - Enum Class in com.jme3.bullet.animation
-
Enumerate algorithms to create a CollisionShape for a PhysicsLink.
- shapeScale(Vector3f) - Method in class com.jme3.bullet.animation.LinkConfig
-
Copy the scale factors used to adjust the size of the shape.
- show(RenderManager, ViewPort) - Method in class com.jme3.bullet.debug.DebugTools
-
Render all the debug geometries to the specified view port.
- SI - Enum constant in enum class com.jme3.bullet.SolverType
-
btSequentialImpulseConstraintSolver/btMultiBodyConstraintSolver: Bullet's original sequential-impulse solver
- SIMD - Static variable in class com.jme3.bullet.SolverMode
-
SIMD
- SIMPLE - Enum constant in enum class com.jme3.bullet.PhysicsSpace.BroadphaseType
-
btSimpleBroadphase: a brute-force reference implementation for debugging purposes
- SimplexCollisionShape - Class in com.jme3.bullet.collision.shapes
-
A simple point, line-segment, triangle, or tetrahedron collision shape based on Bullet's
btBU_Simplex1to4
. - SimplexCollisionShape() - Constructor for class com.jme3.bullet.collision.shapes.SimplexCollisionShape
-
No-argument constructor needed by SavableClassUtil.
- SimplexCollisionShape(AbstractTriangle) - Constructor for class com.jme3.bullet.collision.shapes.SimplexCollisionShape
-
Instantiate a triangular shape based on the specified AbstractTriangle.
- SimplexCollisionShape(LineSegment) - Constructor for class com.jme3.bullet.collision.shapes.SimplexCollisionShape
-
Instantiate a line-segment shape based on the specified LineSegment.
- SimplexCollisionShape(Vector3f) - Constructor for class com.jme3.bullet.collision.shapes.SimplexCollisionShape
-
Instantiate a point shape based on the specified location.
- SimplexCollisionShape(Vector3f[]) - Constructor for class com.jme3.bullet.collision.shapes.SimplexCollisionShape
-
Instantiate a simplex shape based on the specified array.
- SimplexCollisionShape(Vector3f, Vector3f) - Constructor for class com.jme3.bullet.collision.shapes.SimplexCollisionShape
-
Instantiate a line-segment shape based on the specified endpoints.
- SimplexCollisionShape(Vector3f, Vector3f, Vector3f) - Constructor for class com.jme3.bullet.collision.shapes.SimplexCollisionShape
-
Instantiate a triangular shape based on the specified vertices.
- SimplexCollisionShape(Vector3f, Vector3f, Vector3f, Vector3f) - Constructor for class com.jme3.bullet.collision.shapes.SimplexCollisionShape
-
Instantiate a tetrahedral shape based on the specified vertices.
- SimplexCollisionShape(FloatBuffer, int, int) - Constructor for class com.jme3.bullet.collision.shapes.SimplexCollisionShape
-
Instantiate a simplex shape based on the specified FloatBuffer range.
- SixDofJoint - Class in com.jme3.bullet.joints
-
A 6 degree-of-freedom joint based on Bullet's btGeneric6DofConstraint.
- SixDofJoint() - Constructor for class com.jme3.bullet.joints.SixDofJoint
-
No-argument constructor needed by SavableClassUtil.
- SixDofJoint(PhysicsRigidBody, PhysicsRigidBody, Vector3f, Vector3f, boolean) - Constructor for class com.jme3.bullet.joints.SixDofJoint
-
Instantiate a double-ended SixDofJoint.
- SixDofJoint(PhysicsRigidBody, PhysicsRigidBody, Vector3f, Vector3f, Matrix3f, Matrix3f, boolean) - Constructor for class com.jme3.bullet.joints.SixDofJoint
-
Instantiate a double-ended SixDofJoint.
- SixDofJoint(PhysicsRigidBody, Vector3f, Vector3f, Matrix3f, Matrix3f, JointEnd) - Constructor for class com.jme3.bullet.joints.SixDofJoint
-
Instantiate a single-ended SixDofJoint.
- SixDofSpringJoint - Class in com.jme3.bullet.joints
-
A 6 degree-of-freedom joint based on Bullet's btGeneric6DofSpringConstraint.
- SixDofSpringJoint() - Constructor for class com.jme3.bullet.joints.SixDofSpringJoint
-
No-argument constructor needed by SavableClassUtil.
- SixDofSpringJoint(PhysicsRigidBody, PhysicsRigidBody, Vector3f, Vector3f, Matrix3f, Matrix3f, boolean) - Constructor for class com.jme3.bullet.joints.SixDofSpringJoint
-
Instantiate a double-ended SixDofSpringJoint.
- SixDofSpringJoint(PhysicsRigidBody, Vector3f, Vector3f, Matrix3f, Matrix3f, JointEnd) - Constructor for class com.jme3.bullet.joints.SixDofSpringJoint
-
Instantiate a single-ended SixDofSpringJoint.
- sleeping - Static variable in class com.jme3.bullet.collision.Activation
-
a deactivated collision object (native name: ISLAND_SLEEPING)
- SliderJoint - Class in com.jme3.bullet.joints
-
A 2 degree-of-freedom joint based on Bullet's btSliderConstraint.
- SliderJoint() - Constructor for class com.jme3.bullet.joints.SliderJoint
-
No-argument constructor needed by SavableClassUtil.
- SliderJoint(PhysicsRigidBody, PhysicsRigidBody, Vector3f, Vector3f, boolean) - Constructor for class com.jme3.bullet.joints.SliderJoint
-
Instantiate a double-ended SliderJoint.
- SliderJoint(PhysicsRigidBody, PhysicsRigidBody, Vector3f, Vector3f, Matrix3f, Matrix3f, boolean) - Constructor for class com.jme3.bullet.joints.SliderJoint
-
Instantiate a double-ended SliderJoint.
- SliderJoint(PhysicsRigidBody, Vector3f, Vector3f, JointEnd) - Constructor for class com.jme3.bullet.joints.SliderJoint
-
Instantiate a single-ended SliderJoint.
- soft - Static variable in class com.jme3.bullet.collision.PcoType
-
value for a PhysicsSoftBody (native name: CO_SOFT_BODY)
- SoftAngularJoint - Class in com.jme3.bullet.joints
-
A SoftPhysicsJoint that allows rotation around an axis, based on Bullet's btSoftBody::AJoint.
- SoftAngularJoint() - Constructor for class com.jme3.bullet.joints.SoftAngularJoint
-
No-argument constructor needed by SavableClassUtil.
- SoftAngularJoint(Vector3f, PhysicsSoftBody, int, PhysicsRigidBody) - Constructor for class com.jme3.bullet.joints.SoftAngularJoint
-
Instantiate a soft-rigid angular joint.
- SoftAngularJoint(Vector3f, PhysicsSoftBody, int, PhysicsSoftBody, int) - Constructor for class com.jme3.bullet.joints.SoftAngularJoint
-
Instantiate a soft-soft angular joint.
- SoftBodyConfig - Class in com.jme3.bullet.objects.infos
-
Provide access to fields of the native btSoftBody::Config struct.
- SoftBodyConfig() - Constructor for class com.jme3.bullet.objects.infos.SoftBodyConfig
-
No-argument constructor needed by SavableClassUtil.
- SoftBodyConfig(PhysicsSoftBody) - Constructor for class com.jme3.bullet.objects.infos.SoftBodyConfig
-
Instantiate a config with the default properties.
- SoftBodyControl - Class in com.jme3.bullet.control
-
A PhysicsControl to link a PhysicsSoftBody to a Spatial.
- SoftBodyControl() - Constructor for class com.jme3.bullet.control.SoftBodyControl
-
Instantiate an enabled Control for a soft body based on a single Geometry.
- SoftBodyControl(boolean, boolean, boolean) - Constructor for class com.jme3.bullet.control.SoftBodyControl
-
Instantiate an enabled Control for a soft body based on a single Geometry.
- SoftBodyControl(boolean, boolean, boolean, UseTriangles) - Constructor for class com.jme3.bullet.control.SoftBodyControl
-
Instantiate an enabled Control for a soft body based on a single Geometry.
- SoftBodyMaterial - Class in com.jme3.bullet.objects.infos
-
Provide access to 3 fields of the native btSoftBody::Material struct.
- SoftBodyMaterial() - Constructor for class com.jme3.bullet.objects.infos.SoftBodyMaterial
-
No-argument constructor needed by SavableClassUtil.
- SoftBodyMaterial(PhysicsSoftBody) - Constructor for class com.jme3.bullet.objects.infos.SoftBodyMaterial
-
Instantiate a material with the default properties.
- SoftBodyWorldInfo - Class in com.jme3.bullet
-
Physics-simulation parameters that can be customized for each PhysicsSoftBody, based on Bullet's
btSoftBodyWorldInfo
. - SoftBodyWorldInfo() - Constructor for class com.jme3.bullet.SoftBodyWorldInfo
-
Instantiate an info that refers to a new btSoftBodyWorldInfo with the default parameters.
- SoftBodyWorldInfo(long) - Constructor for class com.jme3.bullet.SoftBodyWorldInfo
-
Instantiate an info that refers to the identified native object.
- SoftDebugAppState - Class in com.jme3.bullet.debug
-
An AppState to manage debug visualization of a PhysicsSoftSpace.
- SoftDebugAppState(DebugConfiguration) - Constructor for class com.jme3.bullet.debug.SoftDebugAppState
-
Instantiate an AppState with the specified configuration.
- SoftHardness - Enum constant in enum class com.jme3.bullet.objects.infos.Sbcp
-
soft-body contact hardness coefficient (≥0, ≤1, default=1, native field: kSHR)
- SoftLinearJoint - Class in com.jme3.bullet.joints
-
A SoftPhysicsJoint based on Bullet's btSoftBody::LJoint.
- SoftLinearJoint() - Constructor for class com.jme3.bullet.joints.SoftLinearJoint
-
No-argument constructor needed by SavableClassUtil.
- SoftLinearJoint(Vector3f, PhysicsSoftBody, int, PhysicsRigidBody) - Constructor for class com.jme3.bullet.joints.SoftLinearJoint
-
Instantiate a soft-rigid linear joint.
- SoftLinearJoint(Vector3f, PhysicsSoftBody, int, PhysicsSoftBody, int) - Constructor for class com.jme3.bullet.joints.SoftLinearJoint
-
Instantiate a soft-soft linear joint.
- SoftPhysicsAppState - Class in com.jme3.bullet
-
An AppState to manage a single PhysicsSoftSpace.
- SoftPhysicsAppState() - Constructor for class com.jme3.bullet.SoftPhysicsAppState
-
Instantiate an enabled app state with no filters to manage a space with the DBVT broadphase collision-detection algorithm.
- SoftPhysicsJoint - Class in com.jme3.bullet.joints
-
The abstract base class for joining a PhysicsSoftBody to another body, based on Bullet's btSoftBody::Joint.
- SoftPhysicsJoint() - Constructor for class com.jme3.bullet.joints.SoftPhysicsJoint
-
No-argument constructor needed by SavableClassUtil.
- SoftPhysicsJoint(PhysicsSoftBody, int, PhysicsRigidBody) - Constructor for class com.jme3.bullet.joints.SoftPhysicsJoint
-
Instantiate a SoftPhysicsJoint to join a soft-body cluster and a rigid body.
- SoftPhysicsJoint(PhysicsSoftBody, int, PhysicsSoftBody, int) - Constructor for class com.jme3.bullet.joints.SoftPhysicsJoint
-
Instantiate a SoftPhysicsJoint to join 2 soft bodies.
- SolverInfo - Class in com.jme3.bullet
-
Parameters used by the contact-and-constraint solver, based on Bullet's btContactSolverInfo.
- SolverMode - Class in com.jme3.bullet
-
Named mode bits for contact-and-constraint solvers, based on btSolverMode.
- SolverType - Enum Class in com.jme3.bullet
-
Enumerate the available contact-and-constraint solvers.
- spaceId() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Return the ID of the space where the collision object is added.
- spaceId() - Method in class com.jme3.bullet.MultiBody
-
Determine the ID of the MultiBodySpace to which this MultiBody is added.
- Sphere - Enum constant in enum class com.jme3.bullet.animation.CenterHeuristic
-
center of the smallest enclosing sphere (using Welzl's algorithm)
- Sphere - Enum constant in enum class com.jme3.bullet.animation.ShapeHeuristic
-
centered bounding sphere
- SphereCollisionShape - Class in com.jme3.bullet.collision.shapes
-
A spherical collision shape based on Bullet's
btSphereShape
. - SphereCollisionShape() - Constructor for class com.jme3.bullet.collision.shapes.SphereCollisionShape
-
No-argument constructor needed by SavableClassUtil.
- SphereCollisionShape(float) - Constructor for class com.jme3.bullet.collision.shapes.SphereCollisionShape
-
Instantiate a sphere shape with the specified radius.
- SphereCollisionShape(FloatBuffer, int, int) - Constructor for class com.jme3.bullet.collision.shapes.SphereCollisionShape
-
Instantiate a sphere shape that encloses the sample locations in the specified FloatBuffer range.
- sphereRadius() - Method in class com.jme3.bullet.collision.shapes.SphericalSegment
-
Return the radius of the parent sphere.
- Spherical - Enum constant in enum class com.jme3.bullet.MultiBodyJointType
-
spherical joint (native name: eSpherical)
- SphericalSegment - Class in com.jme3.bullet.collision.shapes
-
A collision shape for a spherical segment with uniform density, based on
btConvexInternalShape
. - SphericalSegment() - Constructor for class com.jme3.bullet.collision.shapes.SphericalSegment
-
No-argument constructor needed by SavableClassUtil.
- SphericalSegment(float) - Constructor for class com.jme3.bullet.collision.shapes.SphericalSegment
-
Instantiate a hemisphere with the specified radius.
- SphericalSegment(float, float, float) - Constructor for class com.jme3.bullet.collision.shapes.SphericalSegment
-
Instantiate a spherical segment with the specified dimensions.
- split(Plane) - Method in class com.jme3.bullet.collision.shapes.infos.IndexedMesh
-
Attempt to divide this mesh into 2 meshes.
- split(Triangle) - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Divide this shape into 2 compound shapes.
- split(Triangle) - Method in class com.jme3.bullet.collision.shapes.GImpactCollisionShape
-
Attempt to divide this shape into 2 shapes.
- split(Triangle) - Method in class com.jme3.bullet.collision.shapes.HullCollisionShape
-
Attempt to divide this shape into 2 child shapes.
- split(Triangle) - Method in class com.jme3.bullet.collision.shapes.infos.ChildCollisionShape
-
Attempt to divide this child into 2 children.
- split(Triangle) - Method in class com.jme3.bullet.collision.shapes.infos.CompoundMesh
-
Attempt to divide this mesh into 2 meshes.
- split(Triangle) - Method in class com.jme3.bullet.collision.shapes.MeshCollisionShape
-
Attempt to divide this shape into 2 shapes.
- splitImpulseErp() - Method in class com.jme3.bullet.SolverInfo
-
Determine the error-reduction parameter (ERP) used with split impulse (native field: m_splitImpulseTurnErp).
- splitImpulseThreshold() - Method in class com.jme3.bullet.SolverInfo
-
Determine the minimum degree of penetration at which split impulse would be used, assuming it's not enabled globally (native field: m_splitImpulsePenetrationThreshold).
- startPhysics() - Method in class com.jme3.bullet.BulletAppState
-
Allocate a PhysicsSpace and start simulating physics.
- startPhysicsOnExecutor() - Method in class com.jme3.bullet.BulletAppState
-
Allocate the PhysicsSpace and start simulating physics using ThreadingType.PARALLEL.
- stateAttached(AppStateManager) - Method in class com.jme3.bullet.BulletAppState
-
Transition this state from detached to initializing.
- STATIC_OBJECT - Static variable in class com.jme3.bullet.collision.CollisionFlag
-
flag for a static object
- steer(float) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Alter the steering angle of all front wheels.
- steer(int, float) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Alter the steering angle of the indexed wheel.
- steer(VehicleWheel, float) - Method in class com.jme3.bullet.objects.infos.VehicleController
-
Alter the steering angle of the specified wheel.
- Stiffness - Enum constant in enum class com.jme3.bullet.joints.motors.MotorParam
-
spring's stiffness (m_springStiffness, default=0)
- StopCfm - Enum constant in enum class com.jme3.bullet.joints.motors.MotorParam
-
constraint-force mixing parameter at limits (m_stopCFM, native name: BT_CONSTRAINT_STOP_CFM, default=0)
- StopErp - Enum constant in enum class com.jme3.bullet.joints.motors.MotorParam
-
error-reduction parameter at limits (m_stopERP, native name: BT_CONSTRAINT_STOP_ERP, default=0.2)
- stopPhysics() - Method in class com.jme3.bullet.BulletAppState
-
Stop physics after this state is detached.
- SubSimplexRaytest - Static variable in class com.jme3.bullet.RayTestFlag
-
use the fast/approximate algorithm for ray-versus-convex intersection, which is the default if no flags are set (native value: kF_UseSubSimplexConvexCastRaytest)
- surfaceArea() - Method in class com.jme3.bullet.collision.shapes.infos.IndexedMesh
-
Calculate the (one-sided) surface area of the mesh.
- SurfaceOnly - Enum constant in enum class com.jme3.bullet.FillMode
-
create a hollow skin (native name: SURFACE_ONLY)
- sweepTest(ConvexShape, Transform, Transform) - Method in class com.jme3.bullet.CollisionSpace
-
For compatibility with the jme3-jbullet library.
- sweepTest(ConvexShape, Transform, Transform, List<PhysicsSweepTestResult>) - Method in class com.jme3.bullet.CollisionSpace
-
For compatibility with the jme3-jbullet library.
- sweepTest(ConvexShape, Transform, Transform, List<PhysicsSweepTestResult>, float) - Method in class com.jme3.bullet.CollisionSpace
-
Perform a sweep-collision test and store the results in an existing list, in arbitrary order.
T
- tagSuffix() - Method in enum class com.jme3.bullet.joints.motors.MotorParam
-
Determine the serialization-tag suffix for this parameter.
- TargetVelocity - Enum constant in enum class com.jme3.bullet.joints.motors.MotorParam
-
motor's target velocity (m_targetVelocity, default=0)
- TETRAHEDRON - Enum constant in enum class vhacd.ACDMode
-
m_mode = 1: use tetrahedra
- threadTmpVector - Static variable in class com.jme3.bullet.collision.shapes.CustomConvexShape
-
temporary storage for one vector per thread
- TimeScale - Enum constant in enum class com.jme3.bullet.objects.infos.Sbcp
-
time scale (default=1, native field: timescale)
- toHullShape() - Method in class com.jme3.bullet.collision.shapes.BoxCollisionShape
-
Approximate this shape with a HullCollisionShape.
- toHullShape() - Method in class com.jme3.bullet.collision.shapes.CapsuleCollisionShape
-
Approximate this shape with a HullCollisionShape.
- toHullShape() - Method in class com.jme3.bullet.collision.shapes.ConvexShape
-
Approximate this shape with a HullCollisionShape.
- toHullShape() - Method in class com.jme3.bullet.collision.shapes.CylinderCollisionShape
-
Approximate this shape with a HullCollisionShape.
- toHullShape() - Method in class com.jme3.bullet.collision.shapes.MultiSphere
-
Approximate this shape with a HullCollisionShape.
- toHullShape() - Method in class com.jme3.bullet.collision.shapes.SimplexCollisionShape
-
Approximate this shape with a HullCollisionShape.
- toHullShape() - Method in class com.jme3.bullet.collision.shapes.SphereCollisionShape
-
Approximate this shape with a HullCollisionShape.
- toMap() - Method in class vhacd.VHACDParameters
-
Represent this instance as a Map, in order to make comparisons easier.
- toMap() - Method in class vhacd4.Vhacd4Parameters
-
Represent this instance as a Map, in order to make comparisons easier.
- toOutputStream(OutputStream) - Method in class vhacd.VHACDParameters
-
Write selected parameters to the specified OutputStream.
- toOutputStream(OutputStream) - Method in class vhacd4.Vhacd4Parameters
-
Write all parameters to the specified OutputStream.
- TorsoLink - Class in com.jme3.bullet.animation
-
Link the torso of an animated model to a rigid body in a ragdoll.
- TorsoLink() - Constructor for class com.jme3.bullet.animation.TorsoLink
-
No-argument constructor needed by SavableClassUtil.
- torsoName - Static variable in class com.jme3.bullet.animation.DacConfiguration
-
name for the ragdoll's torso, must not be used for any bone
- toSplittableShape() - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Approximate this shape with a splittable shape.
- toSplittableShape() - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Approximate this shape with a splittable shape.
- toSplittableShape() - Method in class com.jme3.bullet.collision.shapes.ConvexShape
-
Approximate this shape with a splittable shape.
- toSplittableShape() - Method in class com.jme3.bullet.collision.shapes.HeightfieldCollisionShape
-
Approximate this shape with a splittable shape.
- toString() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Represent the collision object as a
String
. - toString() - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Represent this CollisionShape as a String.
- toString() - Method in class com.jme3.bullet.joints.PhysicsJoint
-
Represent this joint as a String.
- toString() - Method in class com.jme3.bullet.NativePhysicsObject
-
Represent this instance as a String.
- toString() - Method in class vhacd.VHACDParameters
-
Represent this instance as a String.
- toString() - Method in class vhacd4.Vhacd4Parameters
-
Represent this instance as a String.
- totalAppliedForce(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Determine the total force applied to the body (excluding contact forces, damping, and gravity).
- totalAppliedTorque(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Determine the total torque applied to the body (excluding contact forces and damping).
- totalMass() - Method in class com.jme3.bullet.animation.DacConfiguration
-
Calculate the ragdoll's total mass, including attachments.
- totalMass() - Method in class com.jme3.bullet.animation.DacLinks
-
Return the ragdoll's total mass, including attachments.
- Transforms - Enum constant in enum class jme3utilities.minie.DumpFlags
-
transforms in spatials
- translate(Vector3f) - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Apply the specified translation (in the parent's coordinate system) to each child.
- TranslationalLimitMotor - Class in com.jme3.bullet.joints.motors
-
A motor based on Bullet's btTranslationalLimitMotor, used to control the translation of a SixDofJoint.
- TranslationalLimitMotor(long) - Constructor for class com.jme3.bullet.joints.motors.TranslationalLimitMotor
-
Instantiate a motor.
- TranslationMotor - Class in com.jme3.bullet.joints.motors
-
A 3-axis motor based on Bullet's btTranslationalLimitMotor2, used to control the translation of a New6Dof constraint.
- TranslationMotor(long) - Constructor for class com.jme3.bullet.joints.motors.TranslationMotor
-
Instantiate a motor.
- traversalMode() - Method in class com.jme3.bullet.collision.shapes.infos.BoundingValueHierarchy
-
Return the traversal mode (native field: m_traversalMode).
- triangleIndex() - Method in class com.jme3.bullet.collision.PhysicsRayTestResult
-
Read the triangle index at the point of contact.
- triangleIndex() - Method in class com.jme3.bullet.collision.PhysicsSweepTestResult
-
Return the triangle index at the point of contact.
- triangleIndex(int) - Method in class com.jme3.bullet.collision.shapes.infos.BoundingValueHierarchy
-
Return the triangle index of the specified node.
- TwoSphere - Enum constant in enum class com.jme3.bullet.animation.ShapeHeuristic
-
2-sphere hull to approximate the minimal bounding box (good for many bone links)
U
- unassignNativeObject() - Method in class com.jme3.bullet.NativePhysicsObject
-
Unassign (but don't free) the assigned native object, assuming that one is assigned.
- UNIT_X_CHECK - Static variable in class com.jme3.bullet.debug.DebugTools
-
local copy of
Vector3f.UNIT_X
- UNIT_XYZ_CHECK - Static variable in class com.jme3.bullet.debug.DebugTools
-
local copy of
Vector3f.UNIT_XYZ
- UNIT_Y_CHECK - Static variable in class com.jme3.bullet.debug.DebugTools
-
local copy of
Vector3f.UNIT_Y
- UNIT_Z_CHECK - Static variable in class com.jme3.bullet.debug.DebugTools
-
local copy of
Vector3f.UNIT_Z
- unlinkBone(String) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Unlink the BoneLink of the named bone.
- unscaledVolume() - Method in class com.jme3.bullet.collision.shapes.BoxCollisionShape
-
Return the unscaled volume of the box.
- unscaledVolume() - Method in class com.jme3.bullet.collision.shapes.CapsuleCollisionShape
-
Return the unscaled volume of the capsule.
- unscaledVolume() - Method in class com.jme3.bullet.collision.shapes.ConeCollisionShape
-
Return the unscaled volume of the cone.
- unscaledVolume() - Method in class com.jme3.bullet.collision.shapes.CylinderCollisionShape
-
Return the unscaled volume of the cylinder.
- unscaledVolume() - Method in class com.jme3.bullet.collision.shapes.EmptyShape
-
Return the volume of the shape.
- unscaledVolume() - Method in class com.jme3.bullet.collision.shapes.SimplexCollisionShape
-
Calculate the unscaled volume of the simplex.
- unscaledVolume() - Method in class com.jme3.bullet.collision.shapes.SphereCollisionShape
-
Return the unscaled volume of the sphere.
- upAxis() - Method in class com.jme3.bullet.collision.shapes.HeightfieldCollisionShape
-
Return the index of the height axis.
- upAxisIndex() - Method in class com.jme3.bullet.objects.infos.VehicleController
-
Determine the index of the vehicle's up axis.
- upAxisIndex() - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Determine the index of this vehicle's up axis.
- update(double, double, double, String, String) - Method in interface vhacd.VHACDProgressListener
-
Callback invoked (by native code) for progress updates.
- update(float) - Method in class com.jme3.bullet.animation.DacLinks
-
Update this Control.
- update(float) - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Update this Control.
- update(float) - Method in class com.jme3.bullet.BulletAppState
-
Update this state prior to rendering.
- update(float) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Update this Control.
- update(float) - Method in class com.jme3.bullet.control.CharacterControl
-
Update this Control.
- update(float) - Method in class com.jme3.bullet.control.GhostControl
-
Update this Control.
- update(float) - Method in class com.jme3.bullet.control.JoinedBodyControl
-
Update this Control.
- update(float) - Method in class com.jme3.bullet.control.RigidBodyControl
-
Update this Control.
- update(float) - Method in class com.jme3.bullet.control.SoftBodyControl
-
Update this Control.
- update(float) - Method in class com.jme3.bullet.control.VehicleControl
-
Update this Control.
- update(float) - Method in class com.jme3.bullet.debug.BulletDebugAppState
-
Update this state prior to rendering.
- update(float) - Method in class com.jme3.bullet.PhysicsSpace
-
Update the space.
- update(float, int) - Method in interface com.jme3.bullet.ContactManager
-
Update the associated PhysicsSpace.
- update(float, int) - Method in class com.jme3.bullet.DefaultContactManager
-
Update the associated PhysicsSpace.
- update(float, int) - Method in class com.jme3.bullet.PhysicsSpace
-
Update the space.
- update(float, int, boolean, boolean, boolean) - Method in class com.jme3.bullet.PhysicsSpace
-
Update the space.
- updateAxes(Node, boolean) - Method in class com.jme3.bullet.debug.BulletDebugAppState
-
Update the AxesVisualizer for the specified Node.
- updateClusterMesh(PhysicsSoftBody, Mesh, boolean) - Static method in class com.jme3.bullet.util.NativeSoftBodyUtil
-
Update the position buffer of a Mesh from the clusters in the specified soft body.
- updateLocalCoordinateSystem() - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Update the local coordinate system from the localForward and localUp vectors, adapts localForward and localToWorld.
- updateLocalViewDirection() - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Update the character's viewpoint.
- updateMesh(PhysicsSoftBody, IntBuffer, Mesh, boolean, boolean, Transform) - Static method in class com.jme3.bullet.util.NativeSoftBodyUtil
-
Update the position/normal buffers of a Mesh from the nodes in the specified soft body.
- updatePhysicsState() - Method in class com.jme3.bullet.objects.VehicleWheel
-
Update this wheel's location and orientation.
- updatePinMesh(PhysicsSoftBody, Mesh, boolean) - Static method in class com.jme3.bullet.util.NativeSoftBodyUtil
-
Update the position buffer of a Mesh from the pinned nodes in the specified soft body.
- updateScale() - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Synchronize the copied scale factors with the
btCollisionShape
. - updateShapes() - Method in class com.jme3.bullet.debug.BulletDebugAppState
-
Synchronize the collision-shape debug controls and axis visualizers with the collision objects in the PhysicsSpace.
- updateShapes() - Method in class com.jme3.bullet.debug.MultiBodyDebugAppState
-
Synchronize the collision-shape debug controls and axis visualizers with the collision objects in the PhysicsSpace.
- updateShapes() - Method in class com.jme3.bullet.debug.SoftDebugAppState
-
Synchronize the collision-shape debug controls and axis visualizers with the collision objects in the PhysicsSpace.
- updateSolver() - Method in class com.jme3.bullet.MultiBodySpace
-
Replace the existing contact-and-constraint solver with a new one of the correct type.
- updateSolver() - Method in class com.jme3.bullet.PhysicsSpace
-
Replace the existing contact-and-constraint solver with a new one of the correct type.
- updateVelocities() - Method in class com.jme3.bullet.debug.BulletDebugAppState
-
Synchronize the velocity visualizers with the collision objects in the PhysicsSpace.
- updateVelocities() - Method in class com.jme3.bullet.debug.SoftDebugAppState
-
Synchronize the velocity visualizers with the collision objects in the PhysicsSpace.
- updateWheels() - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Used internally.
- updateWheelTransform(VehicleWheel) - Method in class com.jme3.bullet.objects.infos.VehicleController
-
Used internally.
- UpperLimit - Enum constant in enum class com.jme3.bullet.joints.motors.MotorParam
-
constraint upper limit (m_hiLimit/m_upperLimit, default=-1[rot] or 0[translate])
- Use2Directions - Static variable in class com.jme3.bullet.SolverMode
-
use 2 friction directions
- useDeterministicDispatch(boolean) - Method in class com.jme3.bullet.CollisionSpace
-
Enable or disable the "deterministic overlapping pairs" option in the collision dispatcher (native field: m_deterministicOverlappingPairs).
- useGlobalVelocities(boolean) - Method in class com.jme3.bullet.MultiBody
-
Alter whether this MultiBody uses global velocities.
- user - Static variable in class com.jme3.bullet.collision.PcoType
-
unused (native name: CO_USER_TYPE)
- UserData - Enum constant in enum class jme3utilities.minie.DumpFlags
-
user data in spatials
- UserFilter - Class in jme3utilities.minie
-
A simple DebugAppStateFilter that selects physics objects associated with a specific user object.
- UserFilter(Object) - Constructor for class jme3utilities.minie.UserFilter
-
Instantiate a filter for the specified user object.
- userIndex() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Return the collision object's primary user index (native field: m_userIndex).
- userIndex() - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Return the primary user index (native field: m_userIndex).
- userIndex() - Method in class com.jme3.bullet.MultiBody
-
Return the primary user index (native field: m_userIndex).
- userIndex2() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Return the collision object's secondary user index (native field: m_userIndex2).
- userIndex2() - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Return the secondary user index (native field: m_userIndex2).
- userIndex2() - Method in class com.jme3.bullet.MultiBody
-
Return the secondary user index (native field: m_userIndex2).
- userIndex3() - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Return the collision object's tertiary user index (native field: m_userIndex3).
- useRK4(boolean) - Method in class com.jme3.bullet.MultiBody
-
Alter whether this MultiBody uses RK4 integration.
- useScr(boolean) - Method in class com.jme3.bullet.PhysicsSpace
-
Alter whether the space uses Speculative Contact Restitution (native field: m_applySpeculativeContactRestitution).
- UseTriangles - Enum Class in com.jme3.bullet.control
-
Enumerate uses for triangle indices when constructing a SoftBody from a Mesh.
V
- V_OneSided - Enum constant in enum class com.jme3.bullet.objects.infos.Aero
-
Vertex normals are taken as they are.
- V_Point - Enum constant in enum class com.jme3.bullet.objects.infos.Aero
-
Vertex normals are oriented toward velocity.
- V_TwoSided - Enum constant in enum class com.jme3.bullet.objects.infos.Aero
-
Vertex normals are flipped to match velocity.
- V_TwoSidedLiftDrag - Enum constant in enum class com.jme3.bullet.objects.infos.Aero
-
Vertex normals are flipped to match velocity.
- validate(Armature) - Static method in class com.jme3.bullet.animation.RagUtils
-
Validate an Armature for use with DynamicAnimControl.
- validate(Skeleton) - Static method in class com.jme3.bullet.animation.RagUtils
-
Validate a Skeleton for use with DynamicAnimControl.
- validate(Spatial) - Static method in class com.jme3.bullet.animation.RagUtils
-
Validate a model for use with DynamicAnimControl.
- valueOf(String) - Static method in enum class com.jme3.bullet.animation.CenterHeuristic
-
Returns the enum constant of this class with the specified name.
- valueOf(String) - Static method in enum class com.jme3.bullet.animation.KinematicSubmode
-
Returns the enum constant of this class with the specified name.
- valueOf(String) - Static method in enum class com.jme3.bullet.animation.MassHeuristic
-
Returns the enum constant of this class with the specified name.
- valueOf(String) - Static method in enum class com.jme3.bullet.animation.ShapeHeuristic
-
Returns the enum constant of this class with the specified name.
- valueOf(String) - Static method in enum class com.jme3.bullet.BulletAppState.ThreadingType
-
Returns the enum constant of this class with the specified name.
- valueOf(String) - Static method in enum class com.jme3.bullet.control.UseTriangles
-
Returns the enum constant of this class with the specified name.
- valueOf(String) - Static method in enum class com.jme3.bullet.FillMode
-
Returns the enum constant of this class with the specified name.
- valueOf(String) - Static method in enum class com.jme3.bullet.joints.JointEnd
-
Returns the enum constant of this class with the specified name.
- valueOf(String) - Static method in enum class com.jme3.bullet.joints.motors.MotorParam
-
Returns the enum constant of this class with the specified name.
- valueOf(String) - Static method in enum class com.jme3.bullet.MultiBodyJointType
-
Returns the enum constant of this class with the specified name.
- valueOf(String) - Static method in enum class com.jme3.bullet.objects.infos.Aero
-
Returns the enum constant of this class with the specified name.
- valueOf(String) - Static method in enum class com.jme3.bullet.objects.infos.Cluster
-
Returns the enum constant of this class with the specified name.
- valueOf(String) - Static method in enum class com.jme3.bullet.objects.infos.Sbcp
-
Returns the enum constant of this class with the specified name.
- valueOf(String) - Static method in enum class com.jme3.bullet.PhysicsSpace.BroadphaseType
-
Returns the enum constant of this class with the specified name.
- valueOf(String) - Static method in enum class com.jme3.bullet.RotationOrder
-
Returns the enum constant of this class with the specified name.
- valueOf(String) - Static method in enum class com.jme3.bullet.SolverType
-
Returns the enum constant of this class with the specified name.
- valueOf(String) - Static method in enum class jme3utilities.minie.DumpFlags
-
Returns the enum constant of this class with the specified name.
- valueOf(String) - Static method in enum class vhacd.ACDMode
-
Returns the enum constant of this class with the specified name.
- values() - Static method in enum class com.jme3.bullet.animation.CenterHeuristic
-
Returns an array containing the constants of this enum class, in the order they are declared.
- values() - Static method in enum class com.jme3.bullet.animation.KinematicSubmode
-
Returns an array containing the constants of this enum class, in the order they are declared.
- values() - Static method in enum class com.jme3.bullet.animation.MassHeuristic
-
Returns an array containing the constants of this enum class, in the order they are declared.
- values() - Static method in enum class com.jme3.bullet.animation.ShapeHeuristic
-
Returns an array containing the constants of this enum class, in the order they are declared.
- values() - Static method in enum class com.jme3.bullet.BulletAppState.ThreadingType
-
Returns an array containing the constants of this enum class, in the order they are declared.
- values() - Static method in enum class com.jme3.bullet.control.UseTriangles
-
Returns an array containing the constants of this enum class, in the order they are declared.
- values() - Static method in enum class com.jme3.bullet.FillMode
-
Returns an array containing the constants of this enum class, in the order they are declared.
- values() - Static method in enum class com.jme3.bullet.joints.JointEnd
-
Returns an array containing the constants of this enum class, in the order they are declared.
- values() - Static method in enum class com.jme3.bullet.joints.motors.MotorParam
-
Returns an array containing the constants of this enum class, in the order they are declared.
- values() - Static method in enum class com.jme3.bullet.MultiBodyJointType
-
Returns an array containing the constants of this enum class, in the order they are declared.
- values() - Static method in enum class com.jme3.bullet.objects.infos.Aero
-
Returns an array containing the constants of this enum class, in the order they are declared.
- values() - Static method in enum class com.jme3.bullet.objects.infos.Cluster
-
Returns an array containing the constants of this enum class, in the order they are declared.
- values() - Static method in enum class com.jme3.bullet.objects.infos.Sbcp
-
Returns an array containing the constants of this enum class, in the order they are declared.
- values() - Static method in enum class com.jme3.bullet.PhysicsSpace.BroadphaseType
-
Returns an array containing the constants of this enum class, in the order they are declared.
- values() - Static method in enum class com.jme3.bullet.RotationOrder
-
Returns an array containing the constants of this enum class, in the order they are declared.
- values() - Static method in enum class com.jme3.bullet.SolverType
-
Returns an array containing the constants of this enum class, in the order they are declared.
- values() - Static method in enum class jme3utilities.minie.DumpFlags
-
Returns an array containing the constants of this enum class, in the order they are declared.
- values() - Static method in enum class vhacd.ACDMode
-
Returns an array containing the constants of this enum class, in the order they are declared.
- VehicleControl - Class in com.jme3.bullet.control
-
A PhysicsControl to link a PhysicsVehicle to a Spatial.
- VehicleControl() - Constructor for class com.jme3.bullet.control.VehicleControl
-
No-argument constructor needed by SavableClassUtil.
- VehicleControl(CollisionShape) - Constructor for class com.jme3.bullet.control.VehicleControl
-
Instantiate an enabled Control with mass=1 and the specified CollisionShape.
- VehicleControl(CollisionShape, float) - Constructor for class com.jme3.bullet.control.VehicleControl
-
Instantiate an enabled Control with the specified CollisionShape and mass.
- VehicleController - Class in com.jme3.bullet.objects.infos
-
The "action" (controller) portion of a PhysicsVehicle, based on Bullet's btRaycastVehicle.
- VehicleController(PhysicsVehicle, PhysicsSpace) - Constructor for class com.jme3.bullet.objects.infos.VehicleController
-
Instantiate a controller for the specified collision object.
- VehicleTuning - Class in com.jme3.bullet.objects.infos
-
Tuning parameters for a PhysicsVehicle, based on Bullet's btVehicleTuning.
- VehicleTuning() - Constructor for class com.jme3.bullet.objects.infos.VehicleTuning
-
Instantiate an instance with the default parameter values.
- VehicleWheel - Class in com.jme3.bullet.objects
-
Information about one wheel of a vehicle, based on Bullet's
btWheelInfo
. - VehicleWheel() - Constructor for class com.jme3.bullet.objects.VehicleWheel
-
No-argument constructor needed by SavableClassUtil.
- VehicleWheel(Spatial, Vector3f, Vector3f, Vector3f, float, float, boolean) - Constructor for class com.jme3.bullet.objects.VehicleWheel
-
Instantiate a wheel.
- velocity(Vector3f) - Method in class com.jme3.bullet.animation.PhysicsLink
-
Copy the body's linear velocity, or an estimate thereof.
- VelocityCorrection - Enum constant in enum class com.jme3.bullet.objects.infos.Sbcp
-
velocity correction factor (Baumgarte) (default=1, native field: kVCF)
- velocityIterations() - Method in class com.jme3.bullet.objects.infos.SoftBodyConfig
-
Return the number of velocity-solver iterations (native field: viterations).
- verifyAddedToSpatial(String) - Method in class com.jme3.bullet.animation.DacLinks
-
Verify that this control is added to a Spatial.
- verifyReadyForDynamicMode(String) - Method in class com.jme3.bullet.animation.DacLinks
-
Verify that this control is ready for dynamic mode, which implies that it is added to a Spatial, added to a PhysicsSpace, and the physics has been stepped.
- versionNumber() - Static method in class com.jme3.bullet.util.NativeLibrary
-
Determine the native library's version string.
- versionShort() - Static method in class jme3utilities.minie.MinieVersion
-
Return the terse version string for this library.
- VertexData - Enum constant in enum class jme3utilities.minie.DumpFlags
-
vertex data in geometries
- VertexHull - Enum constant in enum class com.jme3.bullet.animation.ShapeHeuristic
-
convex hull of mesh vertices (precise but relatively slow)
- VF_DD - Static variable in class com.jme3.bullet.objects.infos.ConfigFlag
-
enable the Vertex-versus-Face handler for soft-versus-soft collisions
- VF_SS - Static variable in class com.jme3.bullet.objects.infos.ConfigFlag
-
enable the Node-versus-Face handler for soft-versus-soft collisions
- vhacd - package vhacd
-
Java API for Khaled Mamou’s Volumetric-Hierarchical Approximate Convex Decomposition (V-HACD) algorithm.
- VHACD - Class in vhacd
-
Utility class to perform Volumetric-Hierarchical Approximate Convex Decomposition on an indexed mesh.
- vhacd4 - package vhacd4
-
Java API for version 4 of Khaled Mamou’s Volumetric-Hierarchical Approximate Convex Decomposition (V-HACD) algorithm.
- Vhacd4 - Class in vhacd4
-
Utility class to perform Volumetric-Hierarchical Approximate Convex Decomposition on an indexed mesh.
- Vhacd4Hull - Class in vhacd4
-
A 3-D convex hull based on a V-HACD version 4 ConvexHull.
- Vhacd4Parameters - Class in vhacd4
-
A set of tuning parameters for convex decomposition, based on version 4 of V-HACD's IVHACD::Parameters.
- Vhacd4Parameters() - Constructor for class vhacd4.Vhacd4Parameters
-
Instantiate the default tuning parameters.
- VHACDHull - Class in vhacd
-
A 3-D convex hull based on a V-HACD ConvexHull.
- VHACDParameters - Class in vhacd
-
A set of tuning parameters for convex decomposition, based on classic V-HACD's IVHACD::Parameters.
- VHACDParameters() - Constructor for class vhacd.VHACDParameters
-
Instantiate the default tuning parameters.
- VHACDProgressListener - Interface in vhacd
-
Callback interface from V-HACD, used to report progress.
- volume() - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Calculate the volume of this body.
- volume(CollisionShape) - Static method in class jme3utilities.minie.MyShape
-
Estimate the scaled volume of a closed shape.
- VolumeConservation - Enum constant in enum class com.jme3.bullet.objects.infos.Sbcp
-
volume conservation coefficient (≥0, default=0, native field: kVC)
- volumeConvex() - Method in class com.jme3.bullet.collision.shapes.infos.IndexedMesh
-
Calculate volume of the mesh, assuming it's both closed and convex.
- volumeConvex(ConvexShape, int) - Static method in class com.jme3.bullet.util.DebugShapeFactory
-
Calculate the volume of a debug mesh for the specified convex shape.
- volumeStiffness() - Method in class com.jme3.bullet.objects.infos.SoftBodyMaterial
-
Read the volume-stiffness coefficient (native field: m_kVST).
- VOXEL - Enum constant in enum class vhacd.ACDMode
-
m_mode = 0: use voxels
W
- wantsDeactivation - Static variable in class com.jme3.bullet.collision.Activation
-
a collision object that's timed out but hasn't been deactivated yet? (native name: WANTS_DEACTIVATION)
- WarmStart - Static variable in class com.jme3.bullet.SolverMode
-
use warm start
- warp(Vector3f) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Translate the character instantly to the specified location, provided it's in dynamic mode.
- warp(Vector3f) - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Directly alter the location of the character's center.
- warp(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Directly alter the location of this character's center.
- warpDp(Vec3d) - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Directly alter the location of the character's center.
- waterDensity() - Method in class com.jme3.bullet.SoftBodyWorldInfo
-
Return the water density.
- waterOffset() - Method in class com.jme3.bullet.SoftBodyWorldInfo
-
Return the water offset.
- windVelocity(Vector3f) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Copy the wind velocity.
- worldMax() - Method in class com.jme3.bullet.BulletAppState
-
Copy the maximum coordinate values for AXIS_SWEEP.
- worldMin() - Method in class com.jme3.bullet.BulletAppState
-
Copy the minimum coordinate values for AXIS_SWEEP.
- worldTransform(Transform) - Method in class com.jme3.bullet.MultiBodyLink
-
Determine the transform of this link.
- write(JmeExporter) - Method in class com.jme3.bullet.animation.AttachmentLink
-
Serialize this link to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.animation.BoneLink
-
Serialize this link to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.animation.DacConfiguration
-
Serialize this Control to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.animation.DacLinks
-
Serialize this Control to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.animation.DynamicAnimControl
-
Serialize this Control to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.animation.IKController
-
Serialize this controller to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.animation.IKJoint
-
Serialize this joint to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.animation.LinkConfig
-
Serialize this configuration to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.animation.PhysicsLink
-
Serialize this link to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.animation.PreComposer
-
Serialize this Control to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.animation.RangeOfMotion
-
Serialize this preset to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.animation.TorsoLink
-
Serialize this link to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.collision.PhysicsCollisionObject
-
Serialize the collision object to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.collision.shapes.Box2dShape
-
Serialize the shape to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.collision.shapes.BoxCollisionShape
-
Serialize the shape to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.collision.shapes.CapsuleCollisionShape
-
Serialize the shape to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.collision.shapes.CollisionShape
-
Serialize this shape to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.collision.shapes.CompoundCollisionShape
-
Serialize this shape to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.collision.shapes.ConeCollisionShape
-
Serialize this shape to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.collision.shapes.ConicalFrustum
-
Serialize the shape to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.collision.shapes.Convex2dShape
-
Serialize this shape to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.collision.shapes.CustomConvexShape
-
Serialize this shape to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.collision.shapes.CylinderCollisionShape
-
Serialize this shape to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.collision.shapes.GImpactCollisionShape
-
Serialize this shape to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.collision.shapes.HeightfieldCollisionShape
-
Serialize this shape to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.collision.shapes.HullCollisionShape
-
Serialize this shape to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.collision.shapes.infos.BoundingValueHierarchy
-
Serialize this mesh to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.collision.shapes.infos.ChildCollisionShape
-
Serialize this child to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.collision.shapes.infos.CompoundMesh
-
Serialize this mesh to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.collision.shapes.infos.IndexedMesh
-
Serialize this mesh to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.collision.shapes.MeshCollisionShape
-
Serialize this shape to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.collision.shapes.MinkowskiSum
-
Serialize this shape to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.collision.shapes.MultiSphere
-
Serialize this shape to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.collision.shapes.PlaneCollisionShape
-
Serialize this shape to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.collision.shapes.SimplexCollisionShape
-
Serialize this shape to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.collision.shapes.SphereCollisionShape
-
Serialize this shape to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.collision.shapes.SphericalSegment
-
Serialize the shape to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.control.AbstractPhysicsControl
-
Serialize this Control to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.control.BetterCharacterControl
-
Serialize this Control to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.control.CharacterControl
-
Serialize this Control to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.control.GhostControl
-
Serialize this Control to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.control.JoinedBodyControl
-
Serialize this Control to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.control.RigidBodyControl
-
Serialize this Control to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.control.SoftBodyControl
-
Serialize this Control to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.control.VehicleControl
-
Serialize this Control to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.debug.AbstractPhysicsDebugControl
-
Serialize this Control to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.joints.Anchor
-
Serialize this joint to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.joints.ConeJoint
-
Serialize this joint to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.joints.Constraint
-
Serialize this Constraint to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.joints.GearJoint
-
Serialize this joint to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.joints.HingeJoint
-
Serialize this joint to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.joints.New6Dof
-
Serialize this Constraint to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.joints.NewHinge
-
Serialize this Constraint to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.joints.PhysicsJoint
-
Serialize this joint to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.joints.Point2PointJoint
-
Serialize this joint to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.joints.SixDofJoint
-
Serialize this joint to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.joints.SixDofSpringJoint
-
Serialize this joint to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.joints.SliderJoint
-
Serialize this joint to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.joints.SoftAngularJoint
-
Serialize this joint to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.joints.SoftLinearJoint
-
Serialize this joint to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.joints.SoftPhysicsJoint
-
Serialize this joint to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.MultiBody
-
Serialize this object to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.MultiBodyLink
-
Serialize this object to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.objects.infos.CharacterController
-
Serialize this controller to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.objects.infos.RigidBodyMotionState
-
Serialize this object to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.objects.infos.SoftBodyConfig
-
Serialize this config to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.objects.infos.SoftBodyMaterial
-
Serialize this material to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.objects.infos.VehicleTuning
-
Serialize these parameters, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.objects.MultiBodyCollider
-
Serialize this object to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.objects.PhysicsCharacter
-
Serialize this character to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.objects.PhysicsGhostObject
-
Serialize this object to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.objects.PhysicsRigidBody
-
Serialize the body to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.objects.PhysicsSoftBody
-
Serialize this body to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.objects.PhysicsVehicle
-
Serialize this vehicle to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.objects.VehicleWheel
-
Serialize this wheel to the specified exporter, for example when saving to a J3O file.
- write(JmeExporter) - Method in class com.jme3.bullet.SoftBodyWorldInfo
-
Serialize this info to the specified exporter, for example when saving to a J3O file.
- writeJoints(OutputCapsule) - Method in class com.jme3.bullet.objects.PhysicsBody
-
Serialize joints to the specified OutputCapsule, for example when saving to a J3O file.
X
- XYZ - Enum constant in enum class com.jme3.bullet.RotationOrder
-
X then Y then Z (native name: RO_XYZ)
- XZY - Enum constant in enum class com.jme3.bullet.RotationOrder
-
X then Z then Y (native name: RO_XZY)
Y
- yMax() - Method in class com.jme3.bullet.collision.shapes.SphericalSegment
-
Return the Y offset of the upper base from the center of the parent sphere.
- yMin() - Method in class com.jme3.bullet.collision.shapes.SphericalSegment
-
Return the Y offset of the lower base from the center of the parent sphere.
- YXZ - Enum constant in enum class com.jme3.bullet.RotationOrder
-
Y then X then Z (native name: RO_YXZ)
- YZX - Enum constant in enum class com.jme3.bullet.RotationOrder
-
Y then Z then X (native name: RO_YZX)
Z
- ZERO_CHECK - Static variable in class com.jme3.bullet.debug.DebugTools
-
local copy of
Vector3f.ZERO
- ZXY - Enum constant in enum class com.jme3.bullet.RotationOrder
-
Z then X then Y (native name: RO_ZXY)
- ZYX - Enum constant in enum class com.jme3.bullet.RotationOrder
-
Z then Y then X (native name: RO_ZYX)
All Classes and Interfaces|All Packages|Constant Field Values