Update Files

This commit is contained in:
2025-01-22 16:18:30 +01:00
parent ed4603cf95
commit a36294b518
16718 changed files with 2960346 additions and 0 deletions

View File

@ -0,0 +1,839 @@
// Bullet physics bindings for Haxe
package bullet;
enum abstract CollisionObjectActivationState(Int) from Int to Int {
var ACTIVE_TAG = 1;
var ISLAND_SLEEPING = 2;
var WANTS_DEACTIVATION = 3;
var DISABLE_DEACTIVATION = 4;
var DISABLE_SIMULATION = 5;
}
#if hl
abstract BulletString(hl.Bytes) from hl.Bytes to hl.Bytes {
#else
abstract BulletString(Int) from Int to Int {
#end
public inline function toHaxeString(): String {
#if js
// Not available in currently used version of ammo.js
// TODO remove custom utf8 conversion code when updating ammo
// return js.Syntax.code("Ammo.UTF8ToString({0})", this);
return js_UTF8ToString(this);
#elseif hl
return @:privateAccess String.fromUTF8(this);
#end
}
#if js
function js_UTF8ToString(heapOffset: Int) {
final heap: js.lib.Uint8Array = js.Syntax.code("Ammo.HEAPU8");
var end = heapOffset;
while (heap[end] != 0) {
end++;
}
return haxe.io.Bytes.ofData(heap.buffer).getString(heapOffset, end - heapOffset, UTF8);
}
#end
}
#if hl
typedef Bt = haxe.macro.MacroType<[webidl.Module.build({ idlFile : "Sources/bullet/bullet.idl", chopPrefix : "bt", autoGC : false, nativeLib : "bullet" })]>;
#else
// These will be eventually auto-generated, similar to the above
@:native('Ammo.btTypedObject')
extern class TypedObject {
}
@:native('Ammo.btVector3')
extern class Vector3 {
public function new(x:Float, y:Float, z:Float):Void;
public function setValue(x:Float, y:Float, z:Float):Void;
public function setX(x:Float):Void;
public function setY(y:Float):Void;
public function setZ(z:Float):Void;
public function x():Float;
public function y():Float;
public function z():Float;
public function length():Float;
// public function normalize():Vector3; // Does not return itself in ammo
public function normalize():Void;
}
@:native('Ammo.btQuadWord')
extern class QuadWord {
public function setX(x:Float):Void;
public function setY(y:Float):Void;
public function setZ(z:Float):Void;
public function setW(w:Float):Void;
public function x():Float;
public function y():Float;
public function z():Float;
public function w():Float;
}
@:native('Ammo.btQuaternion')
extern class Quaternion extends QuadWord {
public function new(x:Float, y:Float, z:Float, w:Float):Void;
public function setEuler(yaw:Float, pitch:Float, roll:Float):Void;
public function slerp(q:Quaternion, t:Float):Quaternion;
public function setValue(x:Float, y:Float, z:Float, w:Float):Void;
//public function inverse():Quaternion;
}
@:native('Ammo.btMatrix3x3')
extern class Matrix3x3 {
public function setEulerZYX(ex:Float, ey:Float, ez:Float):Void;
public function getRotation(q:Quaternion):Void;
public function getRow(y:Int):Vector3;
}
@:native('Ammo.btActionInterface')
extern class ActionInterface {
}
@:native('Ammo.btTransform')
extern class Transform {
public function new():Void;
public function setIdentity():Void;
public function setOrigin(inVec:Vector3):Void;
public function getOrigin():Vector3;
public function setRotation(inQuat:Quaternion):Void;
public function getRotation():Quaternion;
//public function inverse():Transform; // Missing in ammo
}
@:native('Ammo.btIDebugDraw')
extern class IDebugDraw {
public function new():Void;
public dynamic function drawLine(from:Vector3, to:Vector3, color:Vector3): Void;
public dynamic function drawContactPoint(pointOnB:Vector3, normalOnB:Vector3, distance:Float, lifeTime:Int, color:Vector3):Void;
public dynamic function reportErrorWarning(warningString:BulletString):Void;
public dynamic function draw3dText(location:Vector3, textString:BulletString):Void;
public dynamic function setDebugMode(debugMode:Int): Void;
public dynamic function getDebugMode():Int;
}
@:native('Ammo.DebugDrawer')
extern class DebugDrawer {
public function new():Void;
public dynamic function drawLine(from:Vector3, to:Vector3, color:Vector3): Void;
public dynamic function drawContactPoint(pointOnB:Vector3, normalOnB:Vector3, distance:Float, lifeTime:Int, color:Vector3):Void;
public dynamic function reportErrorWarning(warningString:BulletString):Void;
public dynamic function draw3dText(location:Vector3, textString:BulletString):Void;
public dynamic function setDebugMode(debugMode:Int): Void;
public dynamic function getDebugMode():Int;
}
@:native('Ammo.btMotionState')
extern class MotionState {
public function getWorldTransform(centerOfMassWorldTrans:Transform):Void;
public function setWorldTransform(centerOfMassWorldTrans:Transform):Void;
}
@:native('Ammo.btDefaultMotionState')
extern class DefaultMotionState extends MotionState {
public function new(worldTrans:Transform, centerOfMassOffset:Transform):Void;
}
@:native('Ammo.btRigidBodyConstructionInfo')
extern class RigidBodyConstructionInfo {
public function new(mass:Float, motionState:MotionState, collisionShape:CollisionShape, localInertia:Vector3):Void;
public var m_friction:Float;
public var m_rollingFriction:Float;
}
@:native('Ammo.btCollisionObject')
extern class CollisionObject {
public static inline var ACTIVE_TAG = CollisionObjectActivationState.ACTIVE_TAG;
public static inline var ISLAND_SLEEPING = CollisionObjectActivationState.ISLAND_SLEEPING;
public static inline var WANTS_DEACTIVATION = CollisionObjectActivationState.WANTS_DEACTIVATION;
public static inline var DISABLE_DEACTIVATION = CollisionObjectActivationState.DISABLE_DEACTIVATION;
public static inline var DISABLE_SIMULATION = CollisionObjectActivationState.DISABLE_SIMULATION;
public function getWorldTransform():Transform;
public function setWorldTransform(trans:Transform):Void;
public function activate(forceActivation:Bool = false):Void;
public function setActivationState(newState:CollisionObjectActivationState):Void;
public function getUserIndex():Int;
public function setUserIndex(index:Int):Void;
public function getUserPointer():Dynamic;
public function setUserPointer(userPointer:Dynamic):Void;
public function isActive():Bool;
public function isKinematicObject():Bool;
public function isStaticObject():Bool;
public function isStaticOrKinematicObject():Bool;
public function setFriction(frict:Float):Void;
public function setRollingFriction(frict:Float):Void;
public function setRestitution(rest:Float):Void;
public function setContactProcessingThreshold(contactProcessingThreshold:Float):Void;
public function setCollisionShape(collisionShape:CollisionShape):Void;
public function getCollisionShape():CollisionShape;
public function setCollisionFlags(flags:Int):Void;
public function getCollisionFlags():Int;
public function setCcdSweptSphereRadius(radius:Float):Void;
public function setCcdMotionThreshold(ccdMotionThreshold:Float):Void;
}
@:native('Ammo.btRigidBody')
extern class RigidBody extends CollisionObject {
public function new(constructionInfo:RigidBodyConstructionInfo):Void;
public function setMassProps(mass:Float, inertia:Vector3):Void;
public function getMotionState():MotionState;
public function applyCentralForce(force:Vector3):Void;
public function applyForce(force:Vector3, rel_pos:Vector3):Void;
public function applyCentralImpulse(impulse:Vector3):Void;
public function applyImpulse(impulse:Vector3, rel_pos:Vector3):Void;
public function applyTorque(torque:Vector3):Void;
public function applyTorqueImpulse(torque:Vector3):Void;
public function clearForces():Void;
public function setDamping(linear:Float, angular:Float):Void;
public function updateInertiaTensor():Void;
// public function getCenterOfMassPosition():Vector3; // Not implemented in Ammo
public function getCenterOfMassTransform():Transform;
public function setCenterOfMassTransform(trans:Transform):Void;
public function getLinearVelocity():Vector3;
public function setLinearVelocity(lin_vel:Vector3):Void;
public function getAngularVelocity():Vector3;
public function setAngularVelocity(ang_vel:Vector3):Void;
public function setLinearFactor(linearFactor:Vector3):Void;
public function setAngularFactor(angFac:Vector3):Void;
public function setSleepingThresholds(linear:Float, angular:Float):Void;
public function applyGravity():Void;
public function getGravity():Vector3;
public function setGravity(acceleration:Vector3):Void;
}
@:native('Ammo.btCollisionConfiguration')
extern class CollisionConfiguration {
}
@:native('Ammo.btDefaultCollisionConfiguration')
extern class DefaultCollisionConfiguration extends CollisionConfiguration {
public function new():Void;
}
@:native('Ammo.btSoftBodyRigidBodyCollisionConfiguration')
extern class SoftBodyRigidBodyCollisionConfiguration extends CollisionConfiguration {
public function new():Void;
}
@:native('Ammo.btDispatcher')
extern class Dispatcher {
public function getManifoldByIndexInternal(index:Int):PersistentManifold;
public function getNumManifolds():Int;
}
@:native('Ammo.btCollisionDispatcher')
extern class CollisionDispatcher extends Dispatcher {
public function new(collisionConfiguration:CollisionConfiguration):Void;
}
@:native('Ammo.btBroadphaseInterface')
extern class BroadphaseInterface {
}
@:native('Ammo.btDbvtBroadphase')
extern class DbvtBroadphase extends BroadphaseInterface {
public function new():Void;
}
@:native('Ammo.btAxisSweep3')
extern class AxisSweep3 extends BroadphaseInterface {
public function new(worldAabbMin:Vector3, worldAabbMax:Vector3):Void;
}
@:native('Ammo.btConstraintSolver')
extern class ConstraintSolver {
}
@:native('Ammo.btSequentialImpulseConstraintSolver')
extern class SequentialImpulseConstraintSolver extends ConstraintSolver {
public function new():Void;
}
@:native('Ammo.btDefaultSoftBodySolver')
extern class DefaultSoftBodySolver extends ConstraintSolver {
public function new():Void;
}
@:native('Ammo.RayResultCallback')
extern class RayResultCallback {
public function hasHit():Bool;
public function new():Void;
public function get_m_collisionFilterGroup():Int;
public function set_m_collisionFilterGroup(g:Int):Void;
public function get_m_collisionFilterMask():Int;
public function set_m_collisionFilterMask(m:Int):Void;
public function get_m_collisionObject():CollisionObject;
}
@:native('Ammo.ClosestRayResultCallback')
extern class ClosestRayResultCallback extends RayResultCallback {
public function new(rayFromWorld:Vector3, rayToWorld:Vector3):Void;
public function get_m_hitNormalWorld():Vector3;
public function get_m_hitPointWorld():Vector3;
}
@:native('Ammo.ConcreteContactResultCallback')
extern class ConcreteContactResultCallback extends RayResultCallback {
public function new():Void;
}
@:native('Ammo.btCollisionWorld')
extern class CollisionWorld {
public function rayTest(rayFromWorld:Vector3, rayToWorld:Vector3, resultCallback:RayResultCallback):Void;
public function updateSingleAabb(colObj:CollisionObject):Void;
public function getPairCache():OverlappingPairCache;
public function addCollisionObject(collisionObject:CollisionObject):Void;
public function removeCollisionObject(collisionObject:CollisionObject):Void;
@:native("addCollisionObject")
public function addCollisionObjectToGroup(collisionObject:CollisionObject, collisionFilterGroup:Int, collisionFilterMask:Int):Void;
public function convexSweepTest(castShape:ConvexShape, from:Transform, to:Transform, resultCallback:ConvexResultCallback, allowedCcdPenetration:Float):Void;
public function setDebugDrawer(debugDrawer:DebugDrawer):Void;
public function getDebugDrawer():DebugDrawer;
public function debugDrawWorld():Void;
}
@:native('Ammo.ConvexResultCallback')
extern class ConvexResultCallback {
public function hasHit():Bool;
public function new():Void;
public function get_m_collisionFilterGroup():Int;
public function set_m_collisionFilterGroup(g:Int):Void;
public function get_m_collisionFilterMask():Int;
public function set_m_collisionFilterMask(m:Int):Void;
public function get_m_closestHitFraction():Float;
}
@:native('Ammo.ClosestConvexResultCallback')
extern class ClosestConvexResultCallback extends ConvexResultCallback {
public function new(convexFromWorld:Vector3, convexToWorld: Vector3):Void;
public function get_m_convexFromWorld():Vector3;
public function get_m_convexToWorld():Vector3;
public function get_m_hitNormalWorld():Vector3;
public function get_m_hitPointWorld():Vector3;
}
@:native('Ammo.btDynamicsWorld')
extern class DynamicsWorld extends CollisionWorld {
public function addRigidBody(body:RigidBody):Void;
@:native("addRigidBody")
public function addRigidBodyToGroup(body:RigidBody, group:Int, mask:Int):Void;
public function removeRigidBody(body:RigidBody):Void;
public function addAction(action:ActionInterface):Void;
public function removeAction(action:ActionInterface):Void;
public function addConstraint(constraint:TypedConstraint, disableCollisionsBetweenLinkedBodies:Bool = false):Void;
public function removeConstraint(constraint:TypedConstraint):Void;
public function getGravity():Vector3;
public function setGravity(v:Vector3):Void;
public function stepSimulation(timeStep:Float, maxSubSteps:Float = 1, fixedTimeStep:Float = 1.0 / 60.0):Void;
}
@:native('Ammo.btDiscreteDynamicsWorld')
extern class DiscreteDynamicsWorld extends DynamicsWorld {
public function new(dispatcher:Dispatcher, pairCache:BroadphaseInterface, constraintSolver:ConstraintSolver, collisionConfiguration:CollisionConfiguration):Void;
}
@:native('Ammo.btSoftBodyWorldInfo')
extern class SoftBodyWorldInfo {
public function set_m_gravity(v:Vector3):Void;
}
@:native('Ammo.btSoftRigidDynamicsWorld')
extern class SoftRigidDynamicsWorld extends DynamicsWorld {
public function new(dispatcher:Dispatcher, pairCache:BroadphaseInterface, constraintSolver:ConstraintSolver, collisionConfiguration:CollisionConfiguration, softConstraintSolver:ConstraintSolver):Void;
public function addSoftBody(body:SoftBody, collisionFilterGroup:Int, collisionFilterMask:Int):Void;
public function removeSoftBody(body:SoftBody):Void;
public function getWorldInfo():SoftBodyWorldInfo;
}
@:native('Ammo.btSimpleDynamicsWorld')
extern class SimpleDynamicsWorld extends DynamicsWorld {
public function new(dispatcher:Dispatcher, pairCache:BroadphaseInterface, constraintSolver:ConstraintSolver, collisionConfiguration:CollisionConfiguration):Void;
}
@:native('Ammo.btCollisionShape')
extern class CollisionShape {
public function calculateLocalInertia(mass:Float, inertia:Vector3):Void;
public function setMargin(margin:Float):Void;
public function setLocalScaling(scaling:Vector3):Void;
public function getLocalScaling():Vector3;
}
@:native('Ammo.btCompoundShape')
extern class CompoundShape extends CollisionShape {
public function new(enableDynamicAabbTree:Bool = true):Void;
public function addChildShape(localTransform:Transform, shape:CollisionShape):Void;
}
@:native('Ammo.btConvexShape')
extern class ConvexShape extends CollisionShape {
}
@:native('Ammo.btConcaveShape')
extern class ConcaveShape extends CollisionShape {
}
@:native('Ammo.btConvexInternalShape')
extern class ConvexInternalShape extends ConvexShape {
}
@:native('Ammo.btPolyhedralConvexShape')
extern class PolyhedralConvexShape extends ConvexInternalShape {
}
@:native('Ammo.btBoxShape')
extern class BoxShape extends PolyhedralConvexShape {
public function new(boxHalfExtents:Vector3):Void;
}
@:native('Ammo.btSphereShape')
extern class SphereShape extends ConvexInternalShape {
public function new(radius:Float):Void;
}
@:native('Ammo.btStaticPlaneShape')
extern class StaticPlaneShape extends ConcaveShape {
public function new(planeNormal:Vector3, planeConstant:Float):Void;
}
@:native('Ammo.btPolyhedralConvexAabbCachingShape')
extern class PolyhedralConvexAabbCachingShape extends PolyhedralConvexShape {
}
@:native('Ammo.btConvexHullShape')
extern class ConvexHullShape extends PolyhedralConvexAabbCachingShape {
public function new():Void;
public function addPoint(point:Vector3, recalculateLocalAabb:Bool = true):Void;
}
@:native('Ammo.btCapsuleShape')
extern class CapsuleShape extends ConvexInternalShape {
public function new(radius:Float, height:Float):Void;
public function getUpAxis():Int;
public function getRadius():Float;
public function getHalfHeight():Float;
}
@:native('Ammo.btCapsuleShapeX')
extern class CapsuleShapeX extends CapsuleShape {
public function new(radius:Float, height:Float):Void;
}
@:native('Ammo.btCapsuleShapeZ')
extern class CapsuleShapeZ extends CapsuleShape {
public function new(radius:Float, height:Float):Void;
}
@:native('Ammo.btCylinderShape')
extern class CylinderShape extends ConvexInternalShape {
public function new(halfExtents:Vector3):Void;
}
@:native('Ammo.btCylinderShapeX')
extern class CylinderShapeX extends CylinderShape {
public function new(halfExtents:Vector3):Void;
}
@:native('Ammo.btCylinderShapeZ')
extern class CylinderShapeZ extends CylinderShape {
public function new(halfExtents:Vector3):Void;
}
@:native('Ammo.btConeShape')
extern class ConeShape extends ConvexInternalShape {
public function new(radius:Float, height:Float):Void;
}
@:native('Ammo.btConeShapeX')
extern class ConeShapeX extends ConeShape {
public function new(radius:Float, height:Float):Void;
}
@:native('Ammo.btConeShapeZ')
extern class ConeShapeZ extends ConeShape {
public function new(radius:Float, height:Float):Void;
}
@:native('Ammo.btHeightfieldTerrainShape')
extern class HeightfieldTerrainShape extends ConcaveShape {
// heightDataType - float, double, integer, short, fixedpoint88, uchar
public function new(heightStickWidth:Int, heightStickLength:Int, heightfieldData:Dynamic, heightScale:Float, minHeight:Float, maxHeight:Float, upAxis:Int, heightDataType:Int, flipQuadEdges:Bool):Void;
}
@:native('Ammo.btStridingMeshInterface')
extern class StridingMeshInterface {
public function new():Void;
}
@:native('Ammo.btIndexedMesh')
extern class IndexedMesh {
public function new():Void;
}
@:native('Ammo.btTriangleIndexVertexArray')
extern class TriangleIndexVertexArray extends StridingMeshInterface {
public function new():Void;
}
@:native('Ammo.btTriangleMesh')
extern class TriangleMesh extends TriangleIndexVertexArray {
public function new(use32bitIndices:Bool = true, use4componentVertices:Bool = true):Void;
public function addTriangle(vertex0:Vector3, vertex1:Vector3, vertex2:Vector3, removeDuplicateVertices:Bool = false):Void;
}
@:native('Ammo.btTriangleMeshShape')
extern class TriangleMeshShape extends ConcaveShape {
public function new(meshInterface:StridingMeshInterface):Void;
}
@:native('Ammo.btBvhTriangleMeshShape')
extern class BvhTriangleMeshShape extends TriangleMeshShape {
public function new(meshInterface:StridingMeshInterface, useQuantizedAabbCompression:Bool, buildBvh:Bool = true):Void;
}
@:native('Ammo.btGImpactMeshShape')
extern class GImpactMeshShape extends ConcaveShape {
public function new(meshInterface:StridingMeshInterface):Void;
public function updateBound():Void;
}
@:native('Ammo.GImpactCollisionAlgorithm')
extern class GImpactCollisionAlgorithm {
public function new():Void;
public function registerAlgorithm(dispatcher:CollisionDispatcher):Void;
}
@:native('Ammo.btVehicleTuning')
extern class VehicleTuning extends ActionInterface {
public function new():Void;
}
@:native('Ammo.btVehicleRaycaster')
extern class VehicleRaycaster {
}
@:native('Ammo.btDefaultVehicleRaycaster')
extern class DefaultVehicleRaycaster extends VehicleRaycaster {
public function new(world:DynamicsWorld):Void;
}
@:native('Ammo.btWheelInfoConstructionInfo')
extern class RaycastInfo {
public var m_contactNormalWS:Vector3;
public var m_contactPointWS:Vector3;
public var m_suspensionLength:Float;
public var m_hardPointWS:Vector3;
public var m_wheelDirectionWS:Vector3;
public var m_wheelAxleWS:Vector3;
public var m_isInContact:Bool;
}
@:native('Ammo.btWheelInfoConstructionInfo')
extern class WheelInfoConstructionInfo {
public function new():Void;
public var m_chassisConnectionCS:Vector3;
public var m_wheelDirectionCS:Vector3;
public var m_wheelAxleCS:Vector3;
public var m_suspensionRestLength:Float;
public var m_maxSuspensionTravelCm:Float;
public var m_wheelRadius:Float;
public var m_suspensionStiffness:Float;
public var m_wheelsDampingCompression:Float;
public var m_wheelsDampingRelaxation:Float;
public var m_frictionSlip:Float;
public var m_maxSuspensionForce:Float;
public var m_bIsFrontWheel:Bool;
}
@:native('Ammo.btWheelInfo')
extern class WheelInfo {
public function new(ci:WheelInfoConstructionInfo):Void;
public var m_raycastInfo:RaycastInfo;
public var m_worldTransform:Transform;
public var m_chassisConnectionPointCS:Vector3;
public var m_wheelDirectionCS:Vector3;
public var m_wheelAxleCS:Vector3;
public var m_suspensionRestLength1:Float;
public var m_maxSuspensionTravelCm:Float;
public function getSuspensionRestLength():Float;
public var m_suspensionStiffness:Float;
public var m_wheelsDampingCompression:Float;
public var m_wheelsDampingRelaxation:Float;
public var m_frictionSlip:Float;
public var m_steering:Float;
public var m_rotation:Float;
public var m_deltaRotation:Float;
public var m_rollInfluence:Float;
public var m_maxSuspensionForce:Float;
public var m_wheelsRadius:Float;
public var m_engineForce:Float;
public var m_brake:Float;
public var m_bIsFrontWheel:Bool;
public var m_clippedInvContactDotSuspension:Float;
public var m_suspensionRelativeVelocity:Float;
public var m_wheelsSuspensionForce:Float;
public var m_skidInfo:Float;
}
@:native('Ammo.btRaycastVehicle')
extern class RaycastVehicle extends ActionInterface {
public function new(tuning:VehicleTuning, chassis:RigidBody, raycaster:VehicleRaycaster):Void;
public function setCoordinateSystem(rightIndex:Int, upIndex:Int, forwardIndex:Int):Void;
public function addWheel(connectionPointCS0:Vector3, wheelDirectionCS0:Vector3, wheelAxleCS:Vector3, suspensionRestLength:Float, wheelRadius:Float, tuning:VehicleTuning, isFrontWheel:Bool):WheelInfo;
public function getNumWheels():Int;
public function getWheelInfo(index:Int):WheelInfo;
public function resetSuspension():Void;
public function getWheelTransformWS(wheelIndex:Int):Transform;
public function updateWheelTransform(wheelIndex:Int, interpolatedTransform:Bool = true):Void;
public function applyEngineForce(force:Float, wheel:Int):Void;
public function setBrake(brake:Float, wheelIndex:Int):Void;
public function setPitchControl(pitch:Float):Void;
public function updateSuspension(deltaTime:Float ):Void;
public function updateFriction(deltaTime:Float ):Void;
public function setSteeringValue(steering:Float, wheel:Int):Void;
public function getRightAxis():Int;
public function getUpAxis():Int;
public function getForwardAxis():Int;
public function getForwardVector():Vector3;
public function getCurrentSpeedKmHour():Float;
}
@:native('Ammo.btPersistentManifold')
extern class PersistentManifold extends TypedObject {
public function new():Void;
public function getBody0():CollisionObject;
public function getBody1():CollisionObject;
public function getNumContacts():Int;
public function getContactPoint(index:Int):ManifoldPoint;
}
@:native('Ammo.btManifoldPoint')
extern class ManifoldPoint {
public function new():Void;
public function get_m_positionWorldOnA():Vector3;
public function get_m_positionWorldOnB():Vector3;
public function get_m_normalWorldOnB():Vector3;
public function getDistance():Float;
public function getAppliedImpulse():Float;
}
@:native('Ammo.btTypedConstraint')
extern class TypedConstraint extends TypedObject {
public function setBreakingImpulseThreshold(threshold:Float):Void;
}
@:native('Ammo.btGeneric6DofConstraint')
extern class Generic6DofConstraint extends TypedConstraint {
//BT_CONSTRAINT_ERP=1,
//BT_CONSTRAINT_STOP_ERP,
//BT_CONSTRAINT_CFM,
//BT_CONSTRAINT_STOP_CFM
public function new(rbB:RigidBody, frameInB:Transform, useLinearReferenceFrameB:Bool):Void;
public static inline function new2(rbA:RigidBody, rbB:RigidBody, frameInA:Transform, frameInB:Transform, useLinearReferenceFrameB:Bool = false):Generic6DofConstraint {
var _r1 = rbA, _r2 = rbB, _fa = frameInA, _fb = frameInB, _b = useLinearReferenceFrameB;
return untyped js.Syntax.code("new Ammo.btGeneric6DofConstraint(_r1, _r2, _fa, _fb, _b)");
}
public function setLinearLowerLimit(linearLower:Vector3):Void;
public function setLinearUpperLimit(linearUpper:Vector3):Void;
public function setAngularLowerLimit(angularLower:Vector3):Void;
public function setAngularUpperLimit(angularUpper:Vector3):Void;
public function setParam(num:Int, value:Float, axis:Int = -1):Void;
public function getFrameOffsetA():Transform;
}
@:native('Ammo.btGeneric6DofSpringConstraint')
extern class Generic6DofSpringConstraint extends Generic6DofConstraint {
public function new(rbA:RigidBody, rbB:RigidBody, frameInA:Transform, frameInB:Transform, useLinearReferenceFrameB:Bool):Void;
public function enableSpring(index:Int, onOff:Bool):Void;
public function setStiffness(index:Int,stiffness:Float):Void;
public function setDamping(index:Int,damping:Float):Void;
}
@:native('Ammo.btHingeConstraint')
extern class HingeConstraint extends TypedConstraint {
public function new(rbA:RigidBody, rbB:RigidBody, pivotInA:Vector3, pivotInB:Vector3, axisInA:Vector3, axisInB:Vector3, useReferenceFrameA:Bool = false):Void;
public function setLimit(low:Float, high:Float, _softness:Float = 0.9, _biasFactor:Float = 0.3, _relaxationFactor:Float = 1.0):Void;
}
@:native('Ammo.btSliderConstraint')
extern class SliderConstraint extends TypedConstraint {
public function new(rbA:RigidBody, rbB:RigidBody, frameInA:Transform, frameInB:Transform, useReferenceFrameA:Bool):Void;
public function setLowerLinLimit(lowerLimit:Float):Void;
public function setUpperLinLimit(upperLimit:Float):Void;
public function setLowerAngLimit(lowerAngLimit:Float):Void;
public function setUpperAngLimit(upperAngLimit:Float):Void;
}
@:native('Ammo.btPoint2PointConstraint')
extern class Point2PointConstraint extends TypedConstraint {
public function new(rbA:RigidBody, rbB:RigidBody, pivotInA:Vector3, pivotInB:Vector3):Void;
public function setPivotA(pivotA:Vector3):Void;
public function setPivotB(pivotB:Vector3):Void;
public function getPivotInA():Vector3;
public function getPivotInB():Vector3;
}
@:native('Ammo.Config')
extern class Config {
public function set_viterations(i:Int):Void;
public function set_piterations(i:Int):Void;
public function set_collisions(i:Int):Void;
public function set_kDF(f:Float):Void;
public function set_kDP(f:Float):Void;
public function set_kPR(f:Float):Void;
public function set_kVC(f:Float):Void;
public function set_kAHR(f:Float):Void;
}
@:native('Ammo.tNodeArray')
extern class TNodeArray {
public function at(i:Int):Node;
public function size():Int;
}
@:native('Ammo.tMaterialArray')
extern class TMaterialArray {
public function at(i:Int):Material;
}
@:native('Ammo.tAnchorArray')
extern class TAnchorArray {
public function new();
public function at(i:Int):Anchor;
public function clear():Void;
public function size():Int;
public function push_back(anc:Anchor):Void;
public function pop_back():Void;
}
@:native('Ammo.Node')
extern class Node {
public function get_m_x():Vector3;
public function get_m_n():Vector3;
}
@:native('Ammo.Material')
extern class Material {
public function new();
public function set_m_kLST(kAST:Float):Void;
public function get_m_kLST():Void;
public function set_m_kAST(kAST:Float):Void;
public function get_m_kAST():Void;
public function set_m_kVST(kVST:Float):Void;
public function get_m_kVST():Float;
public function set_m_flags(flags:Int):Void;
public function get_m_flags():Int;
}
@:native('Ammo.Anchor')
extern class Anchor {
public function set_m_node(node:Node):Void;
public function get_m_node():Node;
public function set_m_local(local:Vector3):Void;
public function get_m_local():Vector3;
public function set_m_body(body:RigidBody):Void;
public function get_m_body():RigidBody;
public function set_m_influence(influence:Float):Void;
public function get_m_influence():Float;
//public function set_m_c0(c0:Matrix3x3):Void;
//public function get_m_c0():Matrix3x3;
public function set_m_c1(c1:Vector3):Void;
public function get_m_c1():Vector3;
public function set_m_c2(c2:Float):Void;
public function get_m_c2():Float;
}
@:native('Ammo.btSoftBody')
extern class SoftBody extends CollisionObject {
public function get_m_nodes():TNodeArray;
public function get_m_cfg():Config;
public function get_m_materials():TMaterialArray;
public function get_m_anchors():TAnchorArray;
public function appendMaterial(): Material;
public function updateBounds(): Void;
public function setTotalMass(mass:Float, fromfaces:Bool = false):Void;
public function generateClusters(k:Int, maxiterations:Int = 8192):Void;
public function generateBendingConstraints(distance:Int, mat:Dynamic = 0):Void;
public function appendNode(x:Vector3, m:Float):Void;
public function appendAnchor(node:Int, body:RigidBody, disableCollisionBetweenLinkedBodies:Bool, influence:Float):Void;
public function appendLink(node:Int, node1:Int, mat:Material, bcheckexist:Bool=false):Void;
public function appendFace(node:Int, node1:Int, node3:Int, mat:Material):Void;
public function addForce(f:Vector3, node:Int):Void;
}
@:native('Ammo.btSoftBodyHelpers')
extern class SoftBodyHelpers {
public function new():Void;
function CreateFromTriMesh(worldInfo:SoftBodyWorldInfo, vertices:haxe.ds.Vector<Float>, triangles:haxe.ds.Vector<Int>, ntriangles:Int, randomizeConstraints:Bool = true):SoftBody;
}
@:native('Ammo.btOverlappingPairCallback')
extern class OverlappingPairCallback {
}
@:native('Ammo.btGhostPairCallback')
extern class GhostPairCallback extends OverlappingPairCallback {
public function new():Void;
}
@:native('Ammo.btOverlappingPairCache')
extern class OverlappingPairCache {
public function setInternalGhostPairCallback(ghostPairCallback:OverlappingPairCallback):Void;
}
@:native('Ammo.btGhostObject')
extern class GhostObject extends CollisionObject {
public function new():Void;
public function getNumOverlappingObjects():Int;
public function getOverlappingObject(index:Int):CollisionObject;
}
@:native('Ammo.btPairCachingGhostObject')
extern class PairCachingGhostObject extends GhostObject {
public function new():Void;
}
@:native('Ammo.btKinematicCharacterController')
extern class KinematicCharacterController extends ActionInterface {
public function new(ghostObject:PairCachingGhostObject, convexShape:ConvexShape, stepHeight:Float, upAxis:Int = 1):Void;
public function setUpAxis(axis:Int):Void; // setUp in cpp
public function jump():Void;
public function setGravity(gravity:Float):Void;
public function getGravity():Float;
public function canJump():Bool;
public function onGround():Bool;
public function setWalkDirection(walkDirection:Vector3):Void;
public function setVelocityForTimeInterval(velocity:Vector3, timeInterval:Float):Void;
public function warp(origin:Vector3):Void;
public function preStep(collisionWorld:CollisionWorld):Void;
public function playerStep(collisionWorld:CollisionWorld, dt:Float):Void;
public function setFallSpeed(fallSpeed:Float):Void;
public function setJumpSpeed(jumpSpeed:Float):Void;
public function setMaxJumpHeight(maxJumpHeight:Float):Void;
public function setMaxSlope(slopeRadians:Float):Void;
public function getMaxSlope():Float;
public function getGhostObject():PairCachingGhostObject;
public function setUseGhostSweepTest(useGhostObjectSweepTest:Bool):Void;
public function setUpInterpolate(value:Bool):Void;
}
@:native('Ammo')
extern class Ammo {
public static function destroy(obj:Dynamic):Void;
public static function castObject(obj:Dynamic, to:Class<Dynamic>):Dynamic;
public static function _malloc(byteSize:Int):Int;
public static var HEAPU8:Dynamic;
public static var HEAPF32:Dynamic;
}
#end

View File

@ -0,0 +1,940 @@
// Linear Math
interface btVector3 {
void btVector3();
void btVector3(float x, float y, float z);
float length();
float x();
float y();
float z();
void setX(float x);
void setY(float y);
void setZ(float z);
void setValue(float x, float y, float z);
void normalize();
[Value] btVector3 rotate([Ref] btVector3 wAxis, float angle);
float dot([Ref] btVector3 v);
[Operator="*=", Ref] btVector3 op_mul(float x);
[Operator="+=", Ref] btVector3 op_add([Ref] btVector3 v);
[Operator="-=", Ref] btVector3 op_sub([Ref] btVector3 v);
};
interface btVector4 {
void btVector4();
void btVector4(float x, float y, float z, float w);
float w();
void setValue(float x, float y, float z, float w);
};
btVector4 implements btVector3;
interface btQuadWord {
float x();
float y();
float z();
float w();
void setX(float x);
void setY(float y);
void setZ(float z);
void setW(float w);
};
interface btQuaternion {
void btQuaternion(float x, float y, float z, float w);
void setValue(float x, float y, float z, float w);
void setEulerZYX(float z, float y, float x);
void setRotation([Ref] btVector3 axis, float angle);
void normalize();
float length2();
float length();
float dot([Ref] btQuaternion q);
[Value] btQuaternion normalized();
[Value] btVector3 getAxis();
[Value] btQuaternion inverse();
float getAngle();
float getAngleShortestPath();
float angle([Ref] btQuaternion q);
float angleShortestPath([Ref] btQuaternion q);
[Operator="+=", Ref] btQuaternion op_add([Ref] btQuaternion q);
[Operator="-=", Ref] btQuaternion op_sub([Ref] btQuaternion q);
[Operator="*=", Ref] btQuaternion op_mul(float s);
[Operator="*=", Ref] btQuaternion op_mulq([Ref] btQuaternion q);
[Operator="/=", Ref] btQuaternion op_div(float s);
};
btQuaternion implements btQuadWord;
interface btMatrix3x3 {
void setEulerZYX(float ex, float ey, float ez);
void getRotation([Ref] btQuaternion q);
[Value] btVector3 getRow(long y);
};
interface btTransform {
void btTransform();
void btTransform([Ref] btQuaternion q, [Ref] btVector3 v);
void setIdentity();
void setOrigin([Ref] btVector3 origin);
void setRotation([Ref] btQuaternion rotation);
[Ref] btVector3 getOrigin();
[Value] btQuaternion getRotation();
[Ref] btMatrix3x3 getBasis();
void setFromOpenGLMatrix(float[] m);
};
interface btMotionState {
void getWorldTransform([Ref] btTransform worldTrans);
void setWorldTransform([Ref] btTransform worldTrans);
};
interface btDefaultMotionState {
void btDefaultMotionState([Ref] optional btTransform startTrans, [Ref] optional btTransform centerOfMassOffset);
[Value] attribute btTransform m_graphicsWorldTrans;
};
btDefaultMotionState implements btMotionState;
// Collision
interface btCollisionObject {
void setAnisotropicFriction([Const, Ref] btVector3 anisotropicFriction, long frictionMode);
btCollisionShape getCollisionShape();
void setContactProcessingThreshold(float contactProcessingThreshold);
void setActivationState(long newState);
void forceActivationState(long newState);
void activate(optional boolean forceActivation);
boolean isActive();
boolean isKinematicObject();
boolean isStaticObject();
boolean isStaticOrKinematicObject();
void setRestitution(float rest);
void setFriction(float frict);
void setRollingFriction(float frict);
[Ref] btTransform getWorldTransform();
long getCollisionFlags();
void setCollisionFlags(long flags);
void setWorldTransform([Const,Ref] btTransform worldTrans);
void setCollisionShape(btCollisionShape collisionShape);
void setCcdMotionThreshold (float ccdMotionThreshold);
void setCcdSweptSphereRadius (float radius);
long getUserIndex();
void setUserIndex(long index);
VoidPtr getUserPointer();
void setUserPointer(VoidPtr userPointer);
};
[NoDelete]
interface btCollisionObjectWrapper {
};
[Prefix="btCollisionWorld::"]
interface RayResultCallback {
// abstract base class, no constructor
boolean hasHit();
attribute short m_collisionFilterGroup;
attribute short m_collisionFilterMask;
[Const] attribute btCollisionObject m_collisionObject;
};
[Prefix="btCollisionWorld::"]
interface ClosestRayResultCallback {
void ClosestRayResultCallback([Const, Ref] btVector3 from, [Const, Ref] btVector3 to);
[Value] attribute btVector3 m_rayFromWorld;
[Value] attribute btVector3 m_rayToWorld;
[Value] attribute btVector3 m_hitNormalWorld;
[Value] attribute btVector3 m_hitPointWorld;
};
ClosestRayResultCallback implements RayResultCallback;
interface btManifoldPoint {
[Const, Ref] btVector3 getPositionWorldOnA();
[Const, Ref] btVector3 getPositionWorldOnB();
[Const] double getAppliedImpulse();
[Const] double getDistance();
[Value] attribute btVector3 m_localPointA;
[Value] attribute btVector3 m_localPointB;
[Value] attribute btVector3 m_positionWorldOnB;
[Value] attribute btVector3 m_positionWorldOnA;
[Value] attribute btVector3 m_normalWorldOnB;
};
[Prefix="btCollisionWorld::"]
interface ContactResultCallback {
float addSingleResult([Ref] btManifoldPoint cp, [Const] btCollisionObjectWrapper colObj0Wrap, long partId0, long index0, [Const] btCollisionObjectWrapper colObj1Wrap, long partId1, long index1);
};
[Prefix="btCollisionWorld::"]
interface LocalShapeInfo {
attribute long m_shapePart;
attribute long m_triangleIndex;
};
[Prefix="btCollisionWorld::"]
interface LocalConvexResult {
void LocalConvexResult([Const] btCollisionObject hitCollisionObject, LocalShapeInfo localShapeInfo, [Const, Ref] btVector3 hitNormalLocal, [Const, Ref] btVector3 hitPointLocal, float hitFraction);
[Const] attribute btCollisionObject m_hitCollisionObject;
attribute LocalShapeInfo m_localShapeInfo;
[Value] attribute btVector3 m_hitNormalLocal;
[Value] attribute btVector3 m_hitPointLocal;
attribute float m_hitFraction;
};
[Prefix="btCollisionWorld::"]
interface ConvexResultCallback {
// abstract base class, no constructor
boolean hasHit();
attribute short m_collisionFilterGroup;
attribute short m_collisionFilterMask;
attribute float m_closestHitFraction;
};
[Prefix="btCollisionWorld::"]
interface ClosestConvexResultCallback {
void ClosestConvexResultCallback([Const, Ref] btVector3 convexFromWorld, [Const, Ref] btVector3 convexToWorld);
[Value] attribute btVector3 m_convexFromWorld;
[Value] attribute btVector3 m_convexToWorld;
[Value] attribute btVector3 m_hitNormalWorld;
[Value] attribute btVector3 m_hitPointWorld;
};
ClosestConvexResultCallback implements ConvexResultCallback;
interface btCollisionShape {
void setLocalScaling([Const, Ref] btVector3 scaling);
void calculateLocalInertia(float mass, [Ref] btVector3 inertia);
void setMargin(float margin);
float getMargin();
};
interface btConvexShape {
};
btConvexShape implements btCollisionShape;
interface btConvexTriangleMeshShape {
void btConvexTriangleMeshShape(btStridingMeshInterface meshInterface, optional boolean calcAabb);
};
btConvexTriangleMeshShape implements btConvexShape;
interface btBoxShape {
void btBoxShape([Ref] btVector3 boxHalfExtents);
void setMargin(float margin);
float getMargin();
};
btBoxShape implements btCollisionShape;
interface btCapsuleShape {
void btCapsuleShape(float radius, float height);
void setMargin(float margin);
float getMargin();
};
btCapsuleShape implements btCollisionShape;
interface btCapsuleShapeX {
void btCapsuleShapeX(float radius, float height);
void setMargin(float margin);
float getMargin();
};
btCapsuleShapeX implements btCapsuleShape;
interface btCapsuleShapeZ {
void btCapsuleShapeZ(float radius, float height);
void setMargin(float margin);
float getMargin();
};
btCapsuleShapeZ implements btCapsuleShape;
interface btCylinderShape {
void btCylinderShape([Ref] btVector3 halfExtents);
void setMargin(float margin);
float getMargin();
};
btCylinderShape implements btCollisionShape;
interface btCylinderShapeX {
void btCylinderShapeX([Ref] btVector3 halfExtents);
void setMargin(float margin);
float getMargin();
};
btCylinderShapeX implements btCylinderShape;
interface btCylinderShapeZ {
void btCylinderShapeZ([Ref] btVector3 halfExtents);
void setMargin(float margin);
float getMargin();
};
btCylinderShapeZ implements btCylinderShape;
interface btSphereShape {
void btSphereShape(float radius);
void setMargin(float margin);
float getMargin();
};
btSphereShape implements btCollisionShape;
interface btConeShape {
void btConeShape(float radius, float height);
};
btConeShape implements btCollisionShape;
interface btConvexHullShape {
void btConvexHullShape();
void addPoint([Const, Ref] btVector3 point, optional boolean recalculateLocalAABB);
void setMargin(float margin);
float getMargin();
};
btConvexHullShape implements btCollisionShape;
interface btConeShapeX {
void btConeShapeX(float radius, float height);
};
btConeShapeX implements btConeShape;
interface btConeShapeZ {
void btConeShapeZ(float radius, float height);
};
btConeShapeZ implements btConeShape;
interface btCompoundShape {
void btCompoundShape(optional boolean enableDynamicAabbTree);
void addChildShape([Const, Ref] btTransform localTransform, btCollisionShape shape);
void removeChildShapeByIndex(long childShapeindex);
[Const] long getNumChildShapes();
btCollisionShape getChildShape(long index);
void setMargin(float margin);
float getMargin();
};
btCompoundShape implements btCollisionShape;
interface btStridingMeshInterface {
};
interface btTriangleMesh {
void btTriangleMesh(optional boolean use32bitIndices, optional boolean use4componentVertices);
void addTriangle([Const, Ref] btVector3 vertex0, [Const, Ref] btVector3 vertex1, [Const, Ref] btVector3 vertex2, optional boolean removeDuplicateVertices);
};
btTriangleMesh implements btStridingMeshInterface;
enum PHY_ScalarType {
"PHY_FLOAT",
"PHY_DOUBLE",
"PHY_INTEGER",
"PHY_SHORT",
"PHY_FIXEDPOINT88",
"PHY_UCHAR"
};
interface btConcaveShape {
};
btConcaveShape implements btCollisionShape;
interface btStaticPlaneShape {
void btStaticPlaneShape([Const, Ref] btVector3 planeNormal, float planeConstant);
};
btStaticPlaneShape implements btConcaveShape;
interface btTriangleMeshShape {
};
btTriangleMeshShape implements btConcaveShape;
interface btBvhTriangleMeshShape {
void btBvhTriangleMeshShape(btStridingMeshInterface meshInterface, boolean useQuantizedAabbCompression, optional boolean buildBvh);
};
btBvhTriangleMeshShape implements btTriangleMeshShape;
interface btHeightfieldTerrainShape {
void btHeightfieldTerrainShape(long heightStickWidth, long heightStickLength, VoidPtr heightfieldData, float heightScale, float minHeight, float maxHeight, long upAxis, PHY_ScalarType hdt, boolean flipQuadEdges);
void setMargin(float margin);
float getMargin();
};
btHeightfieldTerrainShape implements btConcaveShape;
interface btGImpactMeshShape {
void btGImpactMeshShape(btStridingMeshInterface meshInterface);
void updateBound();
void registerAlgorithm(btCollisionDispatcher dispatcher);
};
btGImpactMeshShape implements btConcaveShape;
interface btDefaultCollisionConstructionInfo {
void btDefaultCollisionConstructionInfo();
};
interface btDefaultCollisionConfiguration {
void btDefaultCollisionConfiguration([Ref] optional btDefaultCollisionConstructionInfo info);
};
btDefaultCollisionConfiguration implements btCollisionConfiguration;
interface btPersistentManifold {
void btPersistentManifold();
[Const] btCollisionObject getBody0();
[Const] btCollisionObject getBody1();
long getNumContacts();
[Ref] btManifoldPoint getContactPoint(long index);
};
interface btDispatcher {
long getNumManifolds();
btPersistentManifold getManifoldByIndexInternal(long index);
};
interface btCollisionDispatcher {
void btCollisionDispatcher(btDefaultCollisionConfiguration conf);
};
btCollisionDispatcher implements btDispatcher;
interface btOverlappingPairCallback {
};
interface btOverlappingPairCache {
void setInternalGhostPairCallback(btOverlappingPairCallback ghostPairCallback);
};
interface btAxisSweep3 {
void btAxisSweep3([Ref] btVector3 worldAabbMin, [Ref] btVector3 worldAabbMax, optional long maxHandles, optional btOverlappingPairCache pairCache, optional boolean disableRaycastAccelerator);
};
interface btBroadphaseInterface {
};
interface btCollisionConfiguration {
};
interface btDbvtBroadphase {
void btDbvtBroadphase();
};
btDbvtBroadphase implements btBroadphaseInterface;
// Dynamics
[Prefix="btRigidBody::"]
interface btRigidBodyConstructionInfo {
void btRigidBodyConstructionInfo(float mass, btMotionState motionState, btCollisionShape collisionShape, [Ref] optional btVector3 localInertia);
attribute float m_linearDamping;
attribute float m_angularDamping;
attribute float m_friction;
attribute float m_rollingFriction;
attribute float m_restitution;
attribute float m_linearSleepingThreshold;
attribute float m_angularSleepingThreshold;
attribute boolean m_additionalDamping;
attribute float m_additionalDampingFactor;
attribute float m_additionalLinearDampingThresholdSqr;
attribute float m_additionalAngularDampingThresholdSqr;
attribute float m_additionalAngularDampingFactor;
};
interface btRigidBody {
void btRigidBody([Const, Ref] btRigidBodyConstructionInfo constructionInfo);
[Const, Ref] btTransform getCenterOfMassTransform();
void setCenterOfMassTransform([Const, Ref] btTransform xform);
void setSleepingThresholds(float linear, float angular);
void setDamping(float lin_damping, float ang_damping);
void setMassProps(float mass, [Const, Ref] btVector3 inertia);
void setLinearFactor([Const, Ref] btVector3 linearFactor);
void applyTorque([Const, Ref] btVector3 torque);
void applyForce([Const, Ref] btVector3 force, [Const, Ref] btVector3 rel_pos);
void applyCentralForce([Const, Ref] btVector3 force);
void applyTorqueImpulse([Const, Ref] btVector3 torque);
void applyImpulse([Const, Ref] btVector3 impulse, [Const, Ref] btVector3 rel_pos);
void applyCentralImpulse([Const, Ref] btVector3 impulse);
void updateInertiaTensor();
[Const, Ref] btVector3 getLinearVelocity();
[Const, Ref] btVector3 getAngularVelocity();
void setLinearVelocity([Const, Ref] btVector3 lin_vel);
void setAngularVelocity([Const, Ref] btVector3 ang_vel);
btMotionState getMotionState();
void setMotionState(btMotionState motionState);
void setAngularFactor([Const, Ref] btVector3 angularFactor);
btRigidBody upcast([Const] btCollisionObject colObj);
void getAabb([Ref] btVector3 aabbMin, [Ref] btVector3 aabbMax);
[Const, Ref] btVector3 getGravity();
void setGravity([Const, Ref] btVector3 acceleration);
};
btRigidBody implements btCollisionObject;
interface btConstraintSetting {
void btConstraintSetting();
attribute float m_tau;
attribute float m_damping;
attribute float m_impulseClamp;
};
interface btTypedConstraint {
void enableFeedback(boolean needsFeedback);
[Const] float getBreakingImpulseThreshold();
void setBreakingImpulseThreshold([Const] float threshold);
[Const] float getParam(long num, long axis);
void setParam(long num, float value, long axis);
};
enum btConstraintParams {
"BT_CONSTRAINT_ERP",
"BT_CONSTRAINT_STOP_ERP",
"BT_CONSTRAINT_CFM",
"BT_CONSTRAINT_STOP_CFM"
};
interface btPoint2PointConstraint {
void btPoint2PointConstraint([Ref] btRigidBody rbA, [Ref] btRigidBody rbB, [Ref] btVector3 pivotInA, [Ref] btVector3 pivotInB);
void btPoint2PointConstraint([Ref] btRigidBody rbA, [Ref] btVector3 pivotInA);
void setPivotA([Const, Ref] btVector3 pivotA);
void setPivotB([Const, Ref] btVector3 pivotB);
[Const, Ref] btVector3 getPivotInA();
[Const, Ref] btVector3 getPivotInB();
[Value] attribute btConstraintSetting m_setting;
};
btPoint2PointConstraint implements btTypedConstraint;
interface btGeneric6DofConstraint {
void btGeneric6DofConstraint([Ref] btRigidBody rbA, [Ref] btRigidBody rbB, [Ref] btTransform frameInA, [Ref] btTransform frameInB, boolean useLinearFrameReferenceFrameA);
void btGeneric6DofConstraint([Ref] btRigidBody rbB, [Ref] btTransform frameInB, boolean useLinearFrameReferenceFrameB);
void setLinearLowerLimit([Const, Ref] btVector3 linearLower);
void setLinearUpperLimit([Const, Ref] btVector3 linearUpper);
void setAngularLowerLimit([Const, Ref] btVector3 angularLower);
void setAngularUpperLimit([Const, Ref] btVector3 angularUpper);
[Ref] btTransform getFrameOffsetA();
};
btGeneric6DofConstraint implements btTypedConstraint;
interface btGeneric6DofSpringConstraint {
void btGeneric6DofSpringConstraint([Ref] btRigidBody rbA, [Ref] btRigidBody rbB, [Ref] btTransform frameInA, [Ref] btTransform frameInB, boolean useLinearFrameReferenceFrameA);
void btGeneric6DofSpringConstraint([Ref] btRigidBody rbB, [Ref] btTransform frameInB, boolean useLinearFrameReferenceFrameB);
void enableSpring(long index, boolean onOff);
void setStiffness(long index, float stiffness);
void setDamping(long index, float damping);
};
btGeneric6DofSpringConstraint implements btGeneric6DofConstraint;
interface btSequentialImpulseConstraintSolver {
void btSequentialImpulseConstraintSolver();
};
btSequentialImpulseConstraintSolver implements btConstraintSolver;
interface btConeTwistConstraint {
void btConeTwistConstraint([Ref] btRigidBody rbA, [Ref] btRigidBody rbB, [Ref] btTransform rbAFrame, [Ref] btTransform rbBFrame);
void btConeTwistConstraint([Ref] btRigidBody rbA, [Ref] btTransform rbAFrame);
void setLimit(long limitIndex, float limitValue);
void setAngularOnly(boolean angularOnly);
void setDamping(float damping);
void enableMotor(boolean b);
void setMaxMotorImpulse(float maxMotorImpulse);
void setMaxMotorImpulseNormalized(float maxMotorImpulse);
void setMotorTarget([Const,Ref] btQuaternion q);
void setMotorTargetInConstraintSpace([Const,Ref] btQuaternion q);
};
btConeTwistConstraint implements btTypedConstraint;
interface btHingeConstraint {
void btHingeConstraint ([Ref] btRigidBody rbA, [Ref] btRigidBody rbB, [Ref] btVector3 pivotInA, [Ref] btVector3 pivotInB, [Ref] btVector3 axisInA, [Ref] btVector3 axisInB, optional boolean useReferenceFrameA);
void btHingeConstraint ([Ref] btRigidBody rbA, [Ref] btVector3 pivotInA, [Ref] btVector3 axisInA, optional boolean useReferenceFrameA);
//void btHingeConstraint ([Ref] btRigidBody rbA, [Ref] btRigidBody rbB, [Ref] btTransform rbAFrame, [Ref] btTransform rbBFrame, optional boolean useReferenceFrameA);
//void btHingeConstraint ([Ref] btRigidBody rbA, [Ref] btTransform rbAFrame, optional boolean useReferenceFrameA);
void setLimit(float low, float high, float softness, float biasFactor, optional float relaxationFactor);
void enableAngularMotor(boolean enableMotor, float targetVelocity, float maxMotorImpulse);
void setAngularOnly(boolean angularOnly);
void enableMotor(boolean enableMotor);
void setMaxMotorImpulse(float maxMotorImpulse);
void setMotorTarget([Const,Ref] btQuaternion qAinB, float dt);
//void setMotorTarget(float targetAngle, float dt);
};
btHingeConstraint implements btTypedConstraint;
interface btSliderConstraint {
void btSliderConstraint([Ref] btRigidBody rbA, [Ref] btRigidBody rbB, [Const,Ref] btTransform frameInA, [Const,Ref] btTransform frameInB, boolean useLinearReferenceFrameA);
void btSliderConstraint([Ref] btRigidBody rbB, [Const,Ref] btTransform frameInB, boolean useLinearReferenceFrameA);
void setLowerLinLimit(float lowerLimit);
void setUpperLinLimit(float upperLimit);
void setLowerAngLimit(float lowerAngLimit);
void setUpperAngLimit(float upperAngLimit);
};
btSliderConstraint implements btTypedConstraint;
interface btFixedConstraint {
void btFixedConstraint([Ref] btRigidBody rbA, [Ref] btRigidBody rbB, [Const,Ref] btTransform frameInA, [Const,Ref] btTransform frameInB);
};
btFixedConstraint implements btTypedConstraint;
interface btConstraintSolver {
};
interface btDispatcherInfo {
attribute float m_timeStep;
attribute long m_stepCount;
attribute long m_dispatchFunc;
attribute float m_timeOfImpact;
attribute boolean m_useContinuous;
attribute boolean m_enableSatConvex;
attribute boolean m_enableSPU;
attribute boolean m_useEpa;
attribute float m_allowedCcdPenetration;
attribute boolean m_useConvexConservativeDistanceUtil;
attribute float m_convexConservativeDistanceThreshold;
};
interface btCollisionWorld {
btDispatcher getDispatcher();
void rayTest([Const, Ref] btVector3 rayFromWorld, [Const, Ref] btVector3 rayToWorld, [Ref] RayResultCallback resultCallback);
btOverlappingPairCache getPairCache();
[Ref] btDispatcherInfo getDispatchInfo();
void addCollisionObject(btCollisionObject collisionObject, optional short collisionFilterGroup, optional short collisionFilterMask);
[Const] btBroadphaseInterface getBroadphase ();
void convexSweepTest([Const] btConvexShape castShape, [Const, Ref] btTransform from, [Const, Ref] btTransform to, [Ref] ConvexResultCallback resultCallback, float allowedCcdPenetration);
void contactPairTest([Const] btCollisionObject colObjA, [Const] btCollisionObject colObjB, [Ref] ContactResultCallback resultCallback);
void contactTest([Const] btCollisionObject colObj, [Ref] ContactResultCallback resultCallback);
void updateSingleAabb(btCollisionObject colObj);
void debugDrawWorld();
};
interface btContactSolverInfo {
attribute long m_splitImpulse;
attribute long m_splitImpulsePenetrationThreshold;
attribute long m_numIterations;
};
interface btDynamicsWorld {
void addAction(btActionInterface action);
void removeAction(btActionInterface action);
[Ref] btContactSolverInfo getSolverInfo();
};
btDynamicsWorld implements btCollisionWorld;
interface btDiscreteDynamicsWorld {
void btDiscreteDynamicsWorld(btDispatcher dispatcher, btBroadphaseInterface pairCache, btConstraintSolver constraintSolver, btCollisionConfiguration collisionConfiguration);
void setGravity([Ref] btVector3 gravity);
[Value] btVector3 getGravity();
void addRigidBody(btRigidBody body);
void addRigidBody(btRigidBody body, short group, short mask);
void removeRigidBody(btRigidBody body);
void addConstraint(btTypedConstraint constraint, optional boolean disableCollisionsBetweenLinkedBodies);
void removeConstraint(btTypedConstraint constraint);
long stepSimulation(float timeStep, optional long maxSubSteps, optional float fixedTimeStep);
};
btDiscreteDynamicsWorld implements btDynamicsWorld;
[Prefix="btRaycastVehicle::"]
interface btVehicleTuning {
void btVehicleTuning();
attribute float m_suspensionStiffness;
attribute float m_suspensionCompression;
attribute float m_suspensionDamping;
attribute float m_maxSuspensionTravelCm;
attribute float m_frictionSlip;
attribute float m_maxSuspensionForce;
};
[Prefix="btDefaultVehicleRaycaster::"]
interface btVehicleRaycasterResult {
[Value] attribute btVector3 m_hitPointInWorld;
[Value] attribute btVector3 m_hitNormalInWorld;
attribute float m_distFraction;
};
interface btVehicleRaycaster {
void castRay ([Const, Ref] btVector3 from, [Const, Ref] btVector3 to, [Const, Ref] btVehicleRaycasterResult result);
};
interface btDefaultVehicleRaycaster {
void btDefaultVehicleRaycaster(btDynamicsWorld world);
};
btDefaultVehicleRaycaster implements btVehicleRaycaster;
[Prefix="btWheelInfo::"]
interface RaycastInfo {
[Value] attribute btVector3 m_contactNormalWS;
[Value] attribute btVector3 m_contactPointWS;
attribute float m_suspensionLength;
[Value] attribute btVector3 m_hardPointWS;
[Value] attribute btVector3 m_wheelDirectionWS;
[Value] attribute btVector3 m_wheelAxleWS;
attribute boolean m_isInContact;
attribute any m_groundObject;
};
interface btWheelInfoConstructionInfo {
[Value] attribute btVector3 m_chassisConnectionCS;
[Value] attribute btVector3 m_wheelDirectionCS;
[Value] attribute btVector3 m_wheelAxleCS;
attribute float m_suspensionRestLength;
attribute float m_maxSuspensionTravelCm;
attribute float m_wheelRadius;
attribute float m_suspensionStiffness;
attribute float m_wheelsDampingCompression;
attribute float m_wheelsDampingRelaxation;
attribute float m_frictionSlip;
attribute float m_maxSuspensionForce;
attribute boolean m_bIsFrontWheel;
};
interface btWheelInfo {
attribute float m_suspensionStiffness;
attribute float m_frictionSlip;
attribute float m_engineForce;
attribute float m_rollInfluence;
attribute float m_suspensionRestLength1;
attribute float m_wheelsRadius;
attribute float m_wheelsDampingCompression;
attribute float m_wheelsDampingRelaxation;
attribute float m_steering;
attribute float m_maxSuspensionForce;
attribute float m_maxSuspensionTravelCm;
attribute float m_wheelsSuspensionForce;
attribute boolean m_bIsFrontWheel;
[Value] attribute RaycastInfo m_raycastInfo;
[Value] attribute btVector3 m_chassisConnectionPointCS;
void btWheelInfo([Ref] btWheelInfoConstructionInfo ci);
float getSuspensionRestLength ();
void updateWheel ([Const, Ref] btRigidBody chassis, [Ref] RaycastInfo raycastInfo);
[Value] attribute btTransform m_worldTransform;
[Value] attribute btVector3 m_wheelDirectionCS;
[Value] attribute btVector3 m_wheelAxleCS;
attribute float m_rotation;
attribute float m_deltaRotation;
attribute float m_brake;
attribute float m_clippedInvContactDotSuspension;
attribute float m_suspensionRelativeVelocity;
attribute float m_skidInfo;
};
interface btActionInterface {
void updateAction (btCollisionWorld collisionWorld, float deltaTimeStep);
};
interface btKinematicCharacterController {
void btKinematicCharacterController(btPairCachingGhostObject ghostObject, btConvexShape convexShape, float stepHeight, [Const,Ref] optional btVector3 upAxis);
void setUp([Const,Ref] btVector3 axis);
void setWalkDirection ([Const,Ref] btVector3 walkDirection);
void setVelocityForTimeInterval ([Const,Ref] btVector3 velocity, float timeInterval);
//void reset ();
void warp ([Const, Ref]btVector3 origin);
void preStep (btCollisionWorld collisionWorld);
void playerStep (btCollisionWorld collisionWorld, float dt);
void setFallSpeed (float fallSpeed);
void setJumpSpeed (float jumpSpeed);
void setMaxJumpHeight (float maxJumpHeight);
boolean canJump ();
void jump ();
void setGravity ([Const,Ref] btVector3 gravity);
[Value] btVector3 getGravity ();
void setMaxSlope (float slopeRadians);
float getMaxSlope ();
btPairCachingGhostObject getGhostObject ();
void setUseGhostSweepTest (boolean useGhostObjectSweepTest);
boolean onGround ();
};
btKinematicCharacterController implements btActionInterface;
interface btRaycastVehicle {
void btRaycastVehicle([Const, Ref] btVehicleTuning tuning, btRigidBody chassis, btVehicleRaycaster raycaster);
void applyEngineForce(float force, long wheel);
void setSteeringValue(float steering, long wheel);
[Const, Ref] btTransform getWheelTransformWS(long wheelIndex);
void updateWheelTransform(long wheelIndex, boolean interpolatedTransform);
[Ref] btWheelInfo addWheel([Const, Ref] btVector3 connectionPointCS0, [Const, Ref] btVector3 wheelDirectionCS0, [Const, Ref] btVector3 wheelAxleCS, float suspensionRestLength, float wheelRadius, [Const, Ref] btVehicleTuning tuning, boolean isFrontWheel);
long getNumWheels();
btRigidBody getRigidBody();
[Ref] btWheelInfo getWheelInfo(long index);
void setBrake(float brake, long wheelIndex);
void setCoordinateSystem(long rightIndex, long upIndex, long forwardIndex);
float getCurrentSpeedKmHour();
[Const, Ref] btTransform getChassisWorldTransform();
float rayCast([Ref] btWheelInfo wheel);
void updateVehicle(float step);
void resetSuspension();
float getSteeringValue(long wheel);
void updateWheelTransformsWS([Ref] btWheelInfo wheel, optional boolean interpolatedTransform);
void setPitchControl(float pitch);
void updateSuspension(float deltaTime);
void updateFriction(float timeStep);
long getRightAxis();
long getUpAxis();
long getForwardAxis();
[Value] btVector3 getForwardVector();
long getUserConstraintType();
void setUserConstraintType(long userConstraintType);
void setUserConstraintId(long uid);
long getUserConstraintId();
};
btRaycastVehicle implements btActionInterface;
interface btGhostObject {
void btGhostObject();
long getNumOverlappingObjects();
btCollisionObject getOverlappingObject(long index);
};
btGhostObject implements btCollisionObject;
interface btPairCachingGhostObject {
void btPairCachingGhostObject();
};
btPairCachingGhostObject implements btGhostObject;
interface btGhostPairCallback {
void btGhostPairCallback();
};
// soft bodies
interface btSoftBodyWorldInfo {
void btSoftBodyWorldInfo();
attribute float air_density;
attribute float water_density;
attribute float water_offset;
attribute float m_maxDisplacement;
[Value] attribute btVector3 water_normal;
attribute btBroadphaseInterface m_broadphase;
attribute btDispatcher m_dispatcher;
[Value] attribute btVector3 m_gravity;
};
[Prefix="btSoftBody::"]
interface Node {
[Value] attribute btVector3 m_x;
[Value] attribute btVector3 m_n;
};
[Prefix="btSoftBody::"]
interface tNodeArray {
[Const] long size();
[Const, Ref] Node at(long n);
};
[Prefix="btSoftBody::"]
interface Material {
attribute float m_kLST;
attribute float m_kAST;
attribute float m_kVST;
attribute long m_flags;
};
[Prefix="btSoftBody::"]
interface tMaterialArray {
[Const] long size();
Material at(long n);
};
[Prefix="btSoftBody::"]
interface Config {
attribute float kVCF;
attribute float kDP;
attribute float kDG;
attribute float kLF;
attribute float kPR;
attribute float kVC;
attribute float kDF;
attribute float kMT;
attribute float kCHR;
attribute float kKHR;
attribute float kSHR;
attribute float kAHR;
attribute float kSRHR_CL;
attribute float kSKHR_CL;
attribute float kSSHR_CL;
attribute float kSR_SPLT_CL;
attribute float kSK_SPLT_CL;
attribute float kSS_SPLT_CL;
attribute float maxvolume;
attribute float timescale;
attribute long viterations;
attribute long piterations;
attribute long diterations;
attribute long citerations;
attribute long collisions;
};
interface btSoftBody {
void btSoftBody(btSoftBodyWorldInfo worldInfo, long node_count, btVector3 x, float[] m);
void btSoftBody(btSoftBodyWorldInfo worldInfo);
[Value] attribute Config m_cfg;
[Value] attribute tNodeArray m_nodes;
[Value] attribute tMaterialArray m_materials;
[Const] boolean checkLink( long node0, long node1);
[Const] boolean checkFace( long node0, long node1, long node2);
Material appendMaterial();
void appendNode( [Const, Ref] btVector3 x, float m);
void updateBounds();
void appendLink( long node0, long node1, Material mat, boolean bcheckexist);
void appendFace( long node0, long node1, long node2, Material mat);
void appendTetra( long node0, long node1, long node2, long node3, Material mat);
void appendAnchor( long node, btRigidBody body, boolean disableCollisionBetweenLinkedBodies, float influence);
[Const] float getTotalMass();
void setTotalMass( float mass, boolean fromfaces);
void setMass(long node, float mass);
void transform( [Const, Ref] btTransform trs);
void translate( [Const, Ref] btVector3 trs);
void rotate( [Const, Ref] btQuaternion rot);
void scale( [Const, Ref] btVector3 scl);
long generateClusters(long k, optional long maxiterations);
btSoftBody upcast([Const] btCollisionObject colObj);
};
btSoftBody implements btCollisionObject;
interface btSoftBodyRigidBodyCollisionConfiguration {
void btSoftBodyRigidBodyCollisionConfiguration([Ref] optional btDefaultCollisionConstructionInfo info);
};
btSoftBodyRigidBodyCollisionConfiguration implements btDefaultCollisionConfiguration;
interface btSoftBodySolver {
};
interface btDefaultSoftBodySolver {
void btDefaultSoftBodySolver ();
};
btDefaultSoftBodySolver implements btSoftBodySolver;
interface btSoftBodyArray {
[Const] long size();
[Const] btSoftBody at(long n);
};
interface btSoftRigidDynamicsWorld {
void btSoftRigidDynamicsWorld(btDispatcher dispatcher, btBroadphaseInterface pairCache, btConstraintSolver constraintSolver, btCollisionConfiguration collisionConfiguration, btSoftBodySolver softBodySolver);
void addSoftBody(btSoftBody body, short collisionFilterGroup, short collisionFilterMask);
void removeSoftBody(btSoftBody body);
void removeCollisionObject(btCollisionObject collisionObject);
[Ref] btSoftBodyWorldInfo getWorldInfo();
[Ref] btSoftBodyArray getSoftBodyArray();
};
btSoftRigidDynamicsWorld implements btDiscreteDynamicsWorld;
interface btSoftBodyHelpers {
void btSoftBodyHelpers();
btSoftBody CreateRope([Ref] btSoftBodyWorldInfo worldInfo, [Const, Ref] btVector3 from, [Const, Ref] btVector3 to, long res, long fixeds);
btSoftBody CreatePatch([Ref] btSoftBodyWorldInfo worldInfo, [Const, Ref] btVector3 corner00, [Const, Ref] btVector3 corner10, [Const, Ref] btVector3 corner01, [Const, Ref] btVector3 corner11, long resx, long resy, long fixeds, boolean gendiags);
btSoftBody CreatePatchUV([Ref] btSoftBodyWorldInfo worldInfo, [Const, Ref] btVector3 corner00, [Const, Ref] btVector3 corner10, [Const, Ref] btVector3 corner01, [Const, Ref] btVector3 corner11, long resx, long resy, long fixeds, boolean gendiags, float[] tex_coords);
btSoftBody CreateEllipsoid([Ref] btSoftBodyWorldInfo worldInfo, [Const, Ref] btVector3 center, [Const, Ref] btVector3 radius, long res);
btSoftBody CreateFromTriMesh([Ref] btSoftBodyWorldInfo worldInfo, float[] vertices, long[] triangles, long ntriangles, boolean randomizeConstraints);
btSoftBody CreateFromConvexHull([Ref] btSoftBodyWorldInfo worldInfo, [Const] btVector3 vertices, long nvertices, boolean randomizeConstraints);
};
interface btFloatArray {
attribute float[] raw;
void btFloatArray(long num);
[Const] long size();
[Const] float at(long n);
[Const] long set(long n, float value);
};
interface btIntArray {
attribute long[] raw;
void btIntArray(long num);
[Const] long size();
[Const] long at(long n);
[Const] long set(long n, long value);
};