diff --git a/extern/bullet/CMakeLists.txt b/extern/bullet/CMakeLists.txt index 6479895078fa..f18c04a369b3 100644 --- a/extern/bullet/CMakeLists.txt +++ b/extern/bullet/CMakeLists.txt @@ -33,688 +33,597 @@ set(INC_SYS ) set(SRC - src/BulletDynamics/Featherstone/btMultiBodyPoint2Point.cpp - src/BulletDynamics/Featherstone/btMultiBodyGearConstraint.cpp - src/BulletDynamics/Featherstone/btMultiBodyFixedConstraint.cpp - src/BulletDynamics/Featherstone/btMultiBodySliderConstraint.cpp - src/BulletDynamics/Featherstone/btMultiBodyJointMotor.cpp - src/BulletDynamics/Featherstone/btMultiBody.cpp - src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp - src/BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.cpp - src/BulletDynamics/Featherstone/btMultiBodyConstraint.cpp - src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp - src/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.cpp - src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.cpp - src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp - src/BulletDynamics/Dynamics/btDiscreteDynamicsWorldMt.cpp - src/BulletDynamics/Dynamics/btSimulationIslandManagerMt.cpp - src/BulletDynamics/Dynamics/btRigidBody.cpp - src/BulletDynamics/Character/btKinematicCharacterController.cpp - src/BulletDynamics/MLCPSolvers/btLemkeAlgorithm.cpp - src/BulletDynamics/MLCPSolvers/btMLCPSolver.cpp - src/BulletDynamics/MLCPSolvers/btDantzigLCP.cpp - src/BulletDynamics/Vehicle/btWheelInfo.cpp - src/BulletDynamics/Vehicle/btRaycastVehicle.cpp - src/BulletDynamics/ConstraintSolver/btBatchedConstraints.cpp - src/BulletDynamics/ConstraintSolver/btGeneric6DofSpringConstraint.cpp - src/BulletDynamics/ConstraintSolver/btPoint2PointConstraint.cpp - src/BulletDynamics/ConstraintSolver/btUniversalConstraint.cpp - src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.cpp - src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.cpp - src/BulletDynamics/ConstraintSolver/btConeTwistConstraint.cpp - src/BulletDynamics/ConstraintSolver/btTypedConstraint.cpp - src/BulletDynamics/ConstraintSolver/btNNCGConstraintSolver.cpp - src/BulletDynamics/ConstraintSolver/btContactConstraint.cpp - src/BulletDynamics/ConstraintSolver/btFixedConstraint.cpp - src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.cpp - src/BulletDynamics/ConstraintSolver/btHinge2Constraint.cpp - src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp - src/BulletDynamics/ConstraintSolver/btSliderConstraint.cpp - src/BulletDynamics/ConstraintSolver/btGearConstraint.cpp - src/BulletDynamics/ConstraintSolver/btSolve2LinearConstraint.cpp - src/BulletDynamics/ConstraintSolver/btHingeConstraint.cpp - src/BulletInverseDynamics/MultiBodyTree.cpp - src/BulletInverseDynamics/details/MultiBodyTreeImpl.cpp - src/BulletInverseDynamics/details/MultiBodyTreeInitCache.cpp - src/BulletInverseDynamics/IDMath.cpp - src/BulletSoftBody/btSoftBodyHelpers.cpp - src/BulletSoftBody/btSoftBody.cpp - src/BulletSoftBody/btSoftMultiBodyDynamicsWorld.cpp - src/BulletSoftBody/btSoftSoftCollisionAlgorithm.cpp - src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.cpp - src/BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.cpp - src/BulletSoftBody/btSoftRigidDynamicsWorld.cpp - src/BulletSoftBody/btSoftRigidDynamicsWorldMt.cpp - src/BulletSoftBody/btDefaultSoftBodySolver.cpp - src/BulletSoftBody/btSoftRigidCollisionAlgorithm.cpp - src/Bullet3Geometry/b3GeometryUtil.cpp - src/Bullet3Geometry/b3ConvexHullComputer.cpp - src/clew/clew.c - src/Bullet3Common/b3Vector3.cpp - src/Bullet3Common/b3Logging.cpp - src/Bullet3Common/b3AlignedAllocator.cpp - src/Bullet3Collision/NarrowPhaseCollision/b3ConvexUtility.cpp - src/Bullet3Collision/NarrowPhaseCollision/b3CpuNarrowPhase.cpp + src/Bullet3Collision/BroadPhaseCollision/b3DynamicBvhBroadphase.cpp src/Bullet3Collision/BroadPhaseCollision/b3DynamicBvh.cpp src/Bullet3Collision/BroadPhaseCollision/b3OverlappingPairCache.cpp - src/Bullet3Collision/BroadPhaseCollision/b3DynamicBvhBroadphase.cpp - src/Bullet3Serialize/Bullet2FileLoader/b3DNA.cpp - src/Bullet3Serialize/Bullet2FileLoader/b3File.cpp - src/Bullet3Serialize/Bullet2FileLoader/b3Chunk.cpp - src/Bullet3Serialize/Bullet2FileLoader/b3BulletFile.cpp - src/Bullet3Serialize/Bullet2FileLoader/b3Serializer.cpp - src/Bullet3OpenCL/BroadphaseCollision/b3GpuSapBroadphase.cpp - src/Bullet3OpenCL/BroadphaseCollision/b3GpuParallelLinearBvhBroadphase.cpp + src/Bullet3Collision/NarrowPhaseCollision/b3ConvexUtility.cpp + src/Bullet3Collision/NarrowPhaseCollision/b3CpuNarrowPhase.cpp + src/Bullet3Common/b3AlignedAllocator.cpp + src/Bullet3Common/b3Logging.cpp + src/Bullet3Common/b3Vector3.cpp + src/Bullet3Dynamics/b3CpuRigidBodyPipeline.cpp + src/Bullet3Dynamics/ConstraintSolver/b3FixedConstraint.cpp + src/Bullet3Dynamics/ConstraintSolver/b3Generic6DofConstraint.cpp + src/Bullet3Dynamics/ConstraintSolver/b3PgsJacobiSolver.cpp + src/Bullet3Dynamics/ConstraintSolver/b3Point2PointConstraint.cpp + src/Bullet3Dynamics/ConstraintSolver/b3TypedConstraint.cpp + src/Bullet3Geometry/b3ConvexHullComputer.cpp + src/Bullet3Geometry/b3GeometryUtil.cpp src/Bullet3OpenCL/BroadphaseCollision/b3GpuGridBroadphase.cpp + src/Bullet3OpenCL/BroadphaseCollision/b3GpuParallelLinearBvhBroadphase.cpp src/Bullet3OpenCL/BroadphaseCollision/b3GpuParallelLinearBvh.cpp - src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp + src/Bullet3OpenCL/BroadphaseCollision/b3GpuSapBroadphase.cpp + src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp src/Bullet3OpenCL/NarrowphaseCollision/b3ContactCache.cpp + src/Bullet3OpenCL/NarrowphaseCollision/b3ConvexHullContact.cpp + src/Bullet3OpenCL/NarrowphaseCollision/b3GjkEpa.cpp src/Bullet3OpenCL/NarrowphaseCollision/b3OptimizedBvh.cpp src/Bullet3OpenCL/NarrowphaseCollision/b3QuantizedBvh.cpp src/Bullet3OpenCL/NarrowphaseCollision/b3StridingMeshInterface.cpp - src/Bullet3OpenCL/NarrowphaseCollision/b3GjkEpa.cpp - src/Bullet3OpenCL/NarrowphaseCollision/b3TriangleIndexVertexArray.cpp - src/Bullet3OpenCL/NarrowphaseCollision/b3ConvexHullContact.cpp src/Bullet3OpenCL/NarrowphaseCollision/b3TriangleCallback.cpp + src/Bullet3OpenCL/NarrowphaseCollision/b3TriangleIndexVertexArray.cpp src/Bullet3OpenCL/NarrowphaseCollision/b3VoronoiSimplexSolver.cpp + src/Bullet3OpenCL/ParallelPrimitives/b3BoundSearchCL.cpp src/Bullet3OpenCL/ParallelPrimitives/b3FillCL.cpp + src/Bullet3OpenCL/ParallelPrimitives/b3LauncherCL.cpp src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanCL.cpp src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanFloat4CL.cpp - src/Bullet3OpenCL/ParallelPrimitives/b3LauncherCL.cpp - src/Bullet3OpenCL/ParallelPrimitives/b3BoundSearchCL.cpp src/Bullet3OpenCL/ParallelPrimitives/b3RadixSort32CL.cpp - src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp - src/Bullet3OpenCL/RigidBody/b3Solver.cpp + src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp + src/Bullet3OpenCL/RigidBody/b3GpuGenericConstraint.cpp + src/Bullet3OpenCL/RigidBody/b3GpuJacobiContactSolver.cpp + src/Bullet3OpenCL/RigidBody/b3GpuNarrowPhase.cpp src/Bullet3OpenCL/RigidBody/b3GpuPgsConstraintSolver.cpp src/Bullet3OpenCL/RigidBody/b3GpuPgsContactSolver.cpp - src/Bullet3OpenCL/RigidBody/b3GpuJacobiContactSolver.cpp src/Bullet3OpenCL/RigidBody/b3GpuRigidBodyPipeline.cpp - src/Bullet3OpenCL/RigidBody/b3GpuNarrowPhase.cpp - src/Bullet3OpenCL/RigidBody/b3GpuGenericConstraint.cpp - src/LinearMath/TaskScheduler/btThreadSupportPosix.cpp - src/LinearMath/TaskScheduler/btTaskScheduler.cpp - src/LinearMath/TaskScheduler/btThreadSupportWin32.cpp - src/LinearMath/btPolarDecomposition.cpp - src/LinearMath/btConvexHull.cpp - src/LinearMath/btSerializer.cpp - src/LinearMath/btAlignedAllocator.cpp - src/LinearMath/btQuickprof.cpp - src/LinearMath/btConvexHullComputer.cpp - src/LinearMath/btSerializer64.cpp - src/LinearMath/btGeometryUtil.cpp - src/LinearMath/btThreads.cpp - src/LinearMath/btVector3.cpp - src/Bullet3Dynamics/b3CpuRigidBodyPipeline.cpp - src/Bullet3Dynamics/ConstraintSolver/b3FixedConstraint.cpp - src/Bullet3Dynamics/ConstraintSolver/b3Generic6DofConstraint.cpp - src/Bullet3Dynamics/ConstraintSolver/b3TypedConstraint.cpp - src/Bullet3Dynamics/ConstraintSolver/b3PgsJacobiSolver.cpp - src/Bullet3Dynamics/ConstraintSolver/b3Point2PointConstraint.cpp - src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.cpp + src/Bullet3OpenCL/RigidBody/b3Solver.cpp + src/Bullet3Serialize/Bullet2FileLoader/b3BulletFile.cpp + src/Bullet3Serialize/Bullet2FileLoader/b3Chunk.cpp + src/Bullet3Serialize/Bullet2FileLoader/b3DNA.cpp + src/Bullet3Serialize/Bullet2FileLoader/b3File.cpp + src/Bullet3Serialize/Bullet2FileLoader/b3Serializer.cpp + src/BulletCollision/BroadphaseCollision/btAxisSweep3.cpp src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.cpp - src/BulletCollision/BroadphaseCollision/btDbvt.cpp - src/BulletCollision/BroadphaseCollision/btQuantizedBvh.cpp - src/BulletCollision/BroadphaseCollision/btDispatcher.cpp src/BulletCollision/BroadphaseCollision/btCollisionAlgorithm.cpp src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.cpp - src/BulletCollision/BroadphaseCollision/btAxisSweep3.cpp + src/BulletCollision/BroadphaseCollision/btDbvt.cpp + src/BulletCollision/BroadphaseCollision/btDispatcher.cpp + src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.cpp + src/BulletCollision/BroadphaseCollision/btQuantizedBvh.cpp src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.cpp - src/BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.cpp + src/BulletCollision/CollisionDispatch/btActivatingCollisionAlgorithm.cpp + src/BulletCollision/CollisionDispatch/btBox2dBox2dCollisionAlgorithm.cpp + src/BulletCollision/CollisionDispatch/btBoxBoxCollisionAlgorithm.cpp + src/BulletCollision/CollisionDispatch/btBoxBoxDetector.cpp + src/BulletCollision/CollisionDispatch/btCollisionDispatcher.cpp + src/BulletCollision/CollisionDispatch/btCollisionDispatcherMt.cpp + src/BulletCollision/CollisionDispatch/btCollisionObject.cpp + src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp src/BulletCollision/CollisionDispatch/btCollisionWorldImporter.cpp src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.cpp - src/BulletCollision/CollisionDispatch/btSphereSphereCollisionAlgorithm.cpp - src/BulletCollision/CollisionDispatch/btCollisionDispatcherMt.cpp - src/BulletCollision/CollisionDispatch/btUnionFind.cpp - src/BulletCollision/CollisionDispatch/btSphereTriangleCollisionAlgorithm.cpp + src/BulletCollision/CollisionDispatch/btCompoundCompoundCollisionAlgorithm.cpp src/BulletCollision/CollisionDispatch/btConvex2dConvex2dAlgorithm.cpp - src/BulletCollision/CollisionDispatch/btCollisionDispatcher.cpp - src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.cpp src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.cpp - src/BulletCollision/CollisionDispatch/btCollisionObject.cpp - src/BulletCollision/CollisionDispatch/btCompoundCompoundCollisionAlgorithm.cpp - src/BulletCollision/CollisionDispatch/btGhostObject.cpp - src/BulletCollision/CollisionDispatch/btSphereBoxCollisionAlgorithm.cpp - src/BulletCollision/CollisionDispatch/btBoxBoxCollisionAlgorithm.cpp - src/BulletCollision/CollisionDispatch/btSimulationIslandManager.cpp - src/BulletCollision/CollisionDispatch/btManifoldResult.cpp + src/BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.cpp src/BulletCollision/CollisionDispatch/btConvexPlaneCollisionAlgorithm.cpp + src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.cpp + src/BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.cpp + src/BulletCollision/CollisionDispatch/btGhostObject.cpp src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.cpp - src/BulletCollision/CollisionDispatch/btBoxBoxDetector.cpp - src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp - src/BulletCollision/CollisionDispatch/btBox2dBox2dCollisionAlgorithm.cpp src/BulletCollision/CollisionDispatch/btInternalEdgeUtility.cpp + src/BulletCollision/CollisionDispatch/btManifoldResult.cpp + src/BulletCollision/CollisionDispatch/btSimulationIslandManager.cpp + src/BulletCollision/CollisionDispatch/btSphereBoxCollisionAlgorithm.cpp + src/BulletCollision/CollisionDispatch/btSphereSphereCollisionAlgorithm.cpp + src/BulletCollision/CollisionDispatch/btSphereTriangleCollisionAlgorithm.cpp + src/BulletCollision/CollisionDispatch/btUnionFind.cpp src/BulletCollision/CollisionDispatch/SphereTriangleDetector.cpp - src/BulletCollision/CollisionDispatch/btActivatingCollisionAlgorithm.cpp - src/BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.cpp - src/BulletCollision/CollisionShapes/btTriangleCallback.cpp - src/BulletCollision/CollisionShapes/btShapeHull.cpp + src/BulletCollision/CollisionShapes/btBox2dShape.cpp + src/BulletCollision/CollisionShapes/btBoxShape.cpp + src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.cpp + src/BulletCollision/CollisionShapes/btCapsuleShape.cpp + src/BulletCollision/CollisionShapes/btCollisionShape.cpp + src/BulletCollision/CollisionShapes/btCompoundShape.cpp + src/BulletCollision/CollisionShapes/btConcaveShape.cpp + src/BulletCollision/CollisionShapes/btConeShape.cpp src/BulletCollision/CollisionShapes/btConvex2dShape.cpp - src/BulletCollision/CollisionShapes/btConvexShape.cpp src/BulletCollision/CollisionShapes/btConvexHullShape.cpp - src/BulletCollision/CollisionShapes/btCapsuleShape.cpp - src/BulletCollision/CollisionShapes/btMultimaterialTriangleMeshShape.cpp - src/BulletCollision/CollisionShapes/btMiniSDF.cpp - src/BulletCollision/CollisionShapes/btHeightfieldTerrainShape.cpp - src/BulletCollision/CollisionShapes/btEmptyShape.cpp + src/BulletCollision/CollisionShapes/btConvexInternalShape.cpp src/BulletCollision/CollisionShapes/btConvexPointCloudShape.cpp + src/BulletCollision/CollisionShapes/btConvexPolyhedron.cpp + src/BulletCollision/CollisionShapes/btConvexShape.cpp + src/BulletCollision/CollisionShapes/btConvexTriangleMeshShape.cpp + src/BulletCollision/CollisionShapes/btCylinderShape.cpp + src/BulletCollision/CollisionShapes/btEmptyShape.cpp + src/BulletCollision/CollisionShapes/btHeightfieldTerrainShape.cpp + src/BulletCollision/CollisionShapes/btMinkowskiSumShape.cpp + src/BulletCollision/CollisionShapes/btMultimaterialTriangleMeshShape.cpp + src/BulletCollision/CollisionShapes/btMultiSphereShape.cpp src/BulletCollision/CollisionShapes/btOptimizedBvh.cpp - src/BulletCollision/CollisionShapes/btCompoundShape.cpp - src/BulletCollision/CollisionShapes/btTriangleIndexVertexMaterialArray.cpp - src/BulletCollision/CollisionShapes/btCollisionShape.cpp + src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.cpp src/BulletCollision/CollisionShapes/btScaledBvhTriangleMeshShape.cpp - src/BulletCollision/CollisionShapes/btCylinderShape.cpp - src/BulletCollision/CollisionShapes/btConcaveShape.cpp + src/BulletCollision/CollisionShapes/btShapeHull.cpp + src/BulletCollision/CollisionShapes/btSphereShape.cpp src/BulletCollision/CollisionShapes/btStaticPlaneShape.cpp - src/BulletCollision/CollisionShapes/btMultiSphereShape.cpp - src/BulletCollision/CollisionShapes/btBoxShape.cpp - src/BulletCollision/CollisionShapes/btTriangleBuffer.cpp + src/BulletCollision/CollisionShapes/btStridingMeshInterface.cpp src/BulletCollision/CollisionShapes/btTetrahedronShape.cpp - src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.cpp + src/BulletCollision/CollisionShapes/btTriangleBuffer.cpp + src/BulletCollision/CollisionShapes/btTriangleCallback.cpp src/BulletCollision/CollisionShapes/btTriangleIndexVertexArray.cpp - src/BulletCollision/CollisionShapes/btStridingMeshInterface.cpp - src/BulletCollision/CollisionShapes/btMinkowskiSumShape.cpp - src/BulletCollision/CollisionShapes/btConvexPolyhedron.cpp - src/BulletCollision/CollisionShapes/btConvexInternalShape.cpp - src/BulletCollision/CollisionShapes/btSdfCollisionShape.cpp - src/BulletCollision/CollisionShapes/btUniformScalingShape.cpp - src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.cpp - src/BulletCollision/CollisionShapes/btConvexTriangleMeshShape.cpp - src/BulletCollision/CollisionShapes/btSphereShape.cpp - src/BulletCollision/CollisionShapes/btBox2dShape.cpp - src/BulletCollision/CollisionShapes/btTriangleMeshShape.cpp - src/BulletCollision/CollisionShapes/btConeShape.cpp + src/BulletCollision/CollisionShapes/btTriangleIndexVertexMaterialArray.cpp src/BulletCollision/CollisionShapes/btTriangleMesh.cpp - src/BulletCollision/Gimpact/gim_contact.cpp - src/BulletCollision/Gimpact/gim_tri_collision.cpp - src/BulletCollision/Gimpact/btGImpactShape.cpp + src/BulletCollision/CollisionShapes/btTriangleMeshShape.cpp + src/BulletCollision/CollisionShapes/btUniformScalingShape.cpp src/BulletCollision/Gimpact/btContactProcessing.cpp - src/BulletCollision/Gimpact/btTriangleShapeEx.cpp - src/BulletCollision/Gimpact/btGImpactBvh.cpp - src/BulletCollision/Gimpact/gim_box_set.cpp src/BulletCollision/Gimpact/btGenericPoolAllocator.cpp - src/BulletCollision/Gimpact/btGImpactQuantizedBvh.cpp + src/BulletCollision/Gimpact/btGImpactBvh.cpp src/BulletCollision/Gimpact/btGImpactCollisionAlgorithm.cpp + src/BulletCollision/Gimpact/btGImpactQuantizedBvh.cpp + src/BulletCollision/Gimpact/btGImpactShape.cpp + src/BulletCollision/Gimpact/btTriangleShapeEx.cpp + src/BulletCollision/Gimpact/gim_box_set.cpp + src/BulletCollision/Gimpact/gim_contact.cpp src/BulletCollision/Gimpact/gim_memory.cpp - src/BulletCollision/NarrowPhaseCollision/btGjkConvexCast.cpp + src/BulletCollision/Gimpact/gim_tri_collision.cpp src/BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.cpp - src/BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.cpp - src/BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.cpp - src/BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.cpp + src/BulletCollision/NarrowPhaseCollision/btConvexCast.cpp + src/BulletCollision/NarrowPhaseCollision/btGjkConvexCast.cpp src/BulletCollision/NarrowPhaseCollision/btGjkEpa2.cpp + src/BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.cpp src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.cpp - src/BulletCollision/NarrowPhaseCollision/btRaycastCallback.cpp - src/BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.cpp - src/BulletCollision/NarrowPhaseCollision/btConvexCast.cpp + src/BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.cpp src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.cpp src/BulletCollision/NarrowPhaseCollision/btPolyhedralContactClipping.cpp - src/BulletDynamics/Dynamics/Bullet-C-API.cpp - src/Extras/ConvexDecomposition/bestfit.cpp - src/Extras/ConvexDecomposition/bestfitobb.cpp - src/Extras/ConvexDecomposition/cd_hull.cpp - src/Extras/ConvexDecomposition/cd_wavefront.cpp - src/Extras/ConvexDecomposition/concavity.cpp - src/Extras/ConvexDecomposition/ConvexBuilder.cpp - src/Extras/ConvexDecomposition/ConvexDecomposition.cpp - src/Extras/ConvexDecomposition/fitsphere.cpp - src/Extras/ConvexDecomposition/float_math.cpp - src/Extras/ConvexDecomposition/meshvolume.cpp - src/Extras/ConvexDecomposition/planetri.cpp - src/Extras/ConvexDecomposition/raytri.cpp - src/Extras/ConvexDecomposition/splitplane.cpp - src/Extras/ConvexDecomposition/vlookup.cpp - src/Extras/GIMPACTUtils/btGImpactConvexDecompositionShape.cpp - src/Extras/HACD/hacdGraph.cpp - src/Extras/HACD/hacdHACD.cpp - src/Extras/HACD/hacdICHull.cpp - src/Extras/HACD/hacdManifoldMesh.cpp - src/Extras/InverseDynamics/btMultiBodyTreeCreator.cpp - src/Extras/InverseDynamics/CloneTreeCreator.cpp - src/Extras/InverseDynamics/CoilCreator.cpp - src/Extras/InverseDynamics/DillCreator.cpp - src/Extras/InverseDynamics/IDRandomUtil.cpp - src/Extras/InverseDynamics/invdyn_bullet_comparison.cpp - src/Extras/InverseDynamics/MultiBodyNameMap.cpp - src/Extras/InverseDynamics/MultiBodyTreeCreator.cpp - src/Extras/InverseDynamics/MultiBodyTreeDebugGraph.cpp - src/Extras/InverseDynamics/RandomTreeCreator.cpp - src/Extras/InverseDynamics/SimpleTreeCreator.cpp - src/Extras/InverseDynamics/User2InternalIndex.cpp - src/Extras/VHACD/src/btConvexHullComputer.cpp - src/Extras/VHACD/src/VHACD.cpp - src/Extras/VHACD/src/vhacdICHull.cpp - src/Extras/VHACD/src/vhacdManifoldMesh.cpp - src/Extras/VHACD/src/vhacdMesh.cpp - src/Extras/VHACD/src/vhacdVolume.cpp - - src/BulletDynamics/Featherstone/btMultiBodyLink.h - src/BulletDynamics/Featherstone/btMultiBodyFixedConstraint.h - src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h - src/BulletDynamics/Featherstone/btMultiBodyPoint2Point.h - src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h - src/BulletDynamics/Featherstone/btMultiBodyConstraint.h - src/BulletDynamics/Featherstone/btMultiBody.h - src/BulletDynamics/Featherstone/btMultiBodyGearConstraint.h - src/BulletDynamics/Featherstone/btMultiBodySliderConstraint.h - src/BulletDynamics/Featherstone/btMultiBodySolverConstraint.h - src/BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.h - src/BulletDynamics/Featherstone/btMultiBodyJointFeedback.h - src/BulletDynamics/Featherstone/btMultiBodyLinkCollider.h - src/BulletDynamics/Featherstone/btMultiBodyJointMotor.h - src/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h - src/BulletDynamics/Dynamics/btDiscreteDynamicsWorldMt.h - src/BulletDynamics/Dynamics/btRigidBody.h - src/BulletDynamics/Dynamics/btActionInterface.h - src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h - src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.h - src/BulletDynamics/Dynamics/btDynamicsWorld.h - src/BulletDynamics/Dynamics/btSimulationIslandManagerMt.h - src/BulletDynamics/Character/btKinematicCharacterController.h - src/BulletDynamics/Character/btCharacterControllerInterface.h - src/BulletDynamics/MLCPSolvers/btDantzigLCP.h - src/BulletDynamics/MLCPSolvers/btPATHSolver.h - src/BulletDynamics/MLCPSolvers/btMLCPSolver.h - src/BulletDynamics/MLCPSolvers/btLemkeAlgorithm.h - src/BulletDynamics/MLCPSolvers/btMLCPSolverInterface.h - src/BulletDynamics/MLCPSolvers/btSolveProjectedGaussSeidel.h - src/BulletDynamics/MLCPSolvers/btDantzigSolver.h - src/BulletDynamics/MLCPSolvers/btLemkeSolver.h - src/BulletDynamics/Vehicle/btVehicleRaycaster.h - src/BulletDynamics/Vehicle/btRaycastVehicle.h - src/BulletDynamics/Vehicle/btWheelInfo.h - src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h - src/BulletDynamics/ConstraintSolver/btConstraintSolver.h - src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.h - src/BulletDynamics/ConstraintSolver/btGearConstraint.h - src/BulletDynamics/ConstraintSolver/btHinge2Constraint.h - src/BulletDynamics/ConstraintSolver/btGeneric6DofSpringConstraint.h - src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.h - src/BulletDynamics/ConstraintSolver/btHingeConstraint.h - src/BulletDynamics/ConstraintSolver/btTypedConstraint.h - src/BulletDynamics/ConstraintSolver/btUniversalConstraint.h - src/BulletDynamics/ConstraintSolver/btNNCGConstraintSolver.h - src/BulletDynamics/ConstraintSolver/btContactConstraint.h - src/BulletDynamics/ConstraintSolver/btSolverConstraint.h - src/BulletDynamics/ConstraintSolver/btSliderConstraint.h - src/BulletDynamics/ConstraintSolver/btConeTwistConstraint.h - src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.h - src/BulletDynamics/ConstraintSolver/btJacobianEntry.h - src/BulletDynamics/ConstraintSolver/btSolve2LinearConstraint.h - src/BulletDynamics/ConstraintSolver/btSolverBody.h - src/BulletDynamics/ConstraintSolver/btBatchedConstraints.h - src/BulletDynamics/ConstraintSolver/btFixedConstraint.h - src/BulletDynamics/ConstraintSolver/btContactSolverInfo.h - src/BulletDynamics/ConstraintSolver/btPoint2PointConstraint.h - src/BulletSoftBody/btSoftBodyData.h - src/BulletSoftBody/btDefaultSoftBodySolver.h - src/BulletSoftBody/btSoftBodySolverVertexBuffer.h - src/BulletSoftBody/btSoftBodyHelpers.h - src/BulletSoftBody/btSoftMultiBodyDynamicsWorld.h - src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.h - src/BulletSoftBody/btSoftRigidDynamicsWorld.h - src/BulletSoftBody/btSoftRigidDynamicsWorldMt.h - src/BulletSoftBody/btSoftRigidCollisionAlgorithm.h - src/BulletSoftBody/btSparseSDF.h - src/BulletSoftBody/btSoftBody.h - src/BulletSoftBody/btSoftBodySolvers.h - src/BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h - src/BulletSoftBody/btSoftSoftCollisionAlgorithm.h - src/BulletSoftBody/btSoftBodyInternals.h + src/BulletCollision/NarrowPhaseCollision/btRaycastCallback.cpp + src/BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.cpp + src/BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.cpp + src/BulletDynamics/Character/btKinematicCharacterController.cpp + src/BulletDynamics/ConstraintSolver/btConeTwistConstraint.cpp + src/BulletDynamics/ConstraintSolver/btContactConstraint.cpp + src/BulletDynamics/ConstraintSolver/btFixedConstraint.cpp + src/BulletDynamics/ConstraintSolver/btGearConstraint.cpp + src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.cpp + src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.cpp + src/BulletDynamics/ConstraintSolver/btGeneric6DofSpringConstraint.cpp + src/BulletDynamics/ConstraintSolver/btHinge2Constraint.cpp + src/BulletDynamics/ConstraintSolver/btHingeConstraint.cpp + src/BulletDynamics/ConstraintSolver/btNNCGConstraintSolver.cpp + src/BulletDynamics/ConstraintSolver/btPoint2PointConstraint.cpp + src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp + src/BulletDynamics/ConstraintSolver/btSliderConstraint.cpp + src/BulletDynamics/ConstraintSolver/btSolve2LinearConstraint.cpp + src/BulletDynamics/ConstraintSolver/btTypedConstraint.cpp + src/BulletDynamics/ConstraintSolver/btUniversalConstraint.cpp + src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp + src/BulletDynamics/Dynamics/btDiscreteDynamicsWorldMt.cpp + src/BulletDynamics/Dynamics/btRigidBody.cpp + src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.cpp + src/BulletDynamics/Dynamics/btSimulationIslandManagerMt.cpp + src/BulletDynamics/Dynamics/Bullet-C-API.cpp + src/BulletDynamics/Featherstone/btMultiBodyConstraint.cpp + src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp + src/BulletDynamics/Featherstone/btMultiBody.cpp + src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp + src/BulletDynamics/Featherstone/btMultiBodyFixedConstraint.cpp + src/BulletDynamics/Featherstone/btMultiBodyGearConstraint.cpp + src/BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.cpp + src/BulletDynamics/Featherstone/btMultiBodyJointMotor.cpp + src/BulletDynamics/Featherstone/btMultiBodyPoint2Point.cpp + src/BulletDynamics/Featherstone/btMultiBodySliderConstraint.cpp + src/BulletDynamics/MLCPSolvers/btDantzigLCP.cpp + src/BulletDynamics/MLCPSolvers/btLemkeAlgorithm.cpp + src/BulletDynamics/MLCPSolvers/btMLCPSolver.cpp + src/BulletDynamics/Vehicle/btRaycastVehicle.cpp + src/BulletDynamics/Vehicle/btWheelInfo.cpp + src/BulletInverseDynamics/details/MultiBodyTreeImpl.cpp + src/BulletInverseDynamics/details/MultiBodyTreeInitCache.cpp + src/BulletInverseDynamics/IDMath.cpp + src/BulletInverseDynamics/MultiBodyTree.cpp + src/BulletSoftBody/btDefaultSoftBodySolver.cpp + src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.cpp + src/BulletSoftBody/btSoftBody.cpp + src/BulletSoftBody/btSoftBodyHelpers.cpp + src/BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.cpp + src/BulletSoftBody/btSoftMultiBodyDynamicsWorld.cpp + src/BulletSoftBody/btSoftRigidCollisionAlgorithm.cpp + src/BulletSoftBody/btSoftRigidDynamicsWorld.cpp + src/BulletSoftBody/btSoftRigidDynamicsWorldMt.cpp + src/BulletSoftBody/btSoftSoftCollisionAlgorithm.cpp + src/LinearMath/btAlignedAllocator.cpp + src/LinearMath/btConvexHullComputer.cpp + src/LinearMath/btConvexHull.cpp + src/LinearMath/btGeometryUtil.cpp + src/LinearMath/btPolarDecomposition.cpp + src/LinearMath/btQuickprof.cpp + src/LinearMath/btSerializer64.cpp + src/LinearMath/btSerializer.cpp + src/LinearMath/btThreads.cpp + src/LinearMath/btVector3.cpp + src/btBulletCollisionCommon.h - src/Bullet3Geometry/b3ConvexHullComputer.h - src/Bullet3Geometry/b3GrahamScan2dConvexHull.h - src/Bullet3Geometry/b3GeometryUtil.h - src/Bullet3Geometry/b3AabbUtil.h - src/clew/clew.h - src/Bullet3Common/shared/b3Int4.h - src/Bullet3Common/shared/b3Quat.h - src/Bullet3Common/shared/b3Float4.h - src/Bullet3Common/shared/b3PlatformDefinitions.h - src/Bullet3Common/shared/b3Mat3x3.h - src/Bullet3Common/shared/b3Int2.h - src/Bullet3Common/b3Scalar.h - src/Bullet3Common/b3StackAlloc.h - src/Bullet3Common/b3Random.h - src/Bullet3Common/b3AlignedObjectArray.h - src/Bullet3Common/b3Matrix3x3.h - src/Bullet3Common/b3CommandLineArgs.h - src/Bullet3Common/b3ResizablePool.h - src/Bullet3Common/b3FileUtils.h - src/Bullet3Common/b3TransformUtil.h - src/Bullet3Common/b3Transform.h - src/Bullet3Common/b3Logging.h - src/Bullet3Common/b3Quaternion.h - src/Bullet3Common/b3QuadWord.h - src/Bullet3Common/b3AlignedAllocator.h - src/Bullet3Common/b3HashMap.h - src/Bullet3Common/b3PoolAllocator.h - src/Bullet3Common/b3MinMax.h - src/Bullet3Common/b3Vector3.h - src/Bullet3Collision/NarrowPhaseCollision/shared/b3ContactConvexConvexSAT.h + src/btBulletDynamicsCommon.h + src/Bullet3Collision/BroadPhaseCollision/b3BroadphaseCallback.h + src/Bullet3Collision/BroadPhaseCollision/b3DynamicBvhBroadphase.h + src/Bullet3Collision/BroadPhaseCollision/b3DynamicBvh.h + src/Bullet3Collision/BroadPhaseCollision/b3OverlappingPairCache.h + src/Bullet3Collision/BroadPhaseCollision/b3OverlappingPair.h + src/Bullet3Collision/BroadPhaseCollision/shared/b3Aabb.h + src/Bullet3Collision/NarrowPhaseCollision/b3Config.h + src/Bullet3Collision/NarrowPhaseCollision/b3Contact4.h + src/Bullet3Collision/NarrowPhaseCollision/b3ConvexUtility.h + src/Bullet3Collision/NarrowPhaseCollision/b3CpuNarrowPhase.h + src/Bullet3Collision/NarrowPhaseCollision/b3RaycastInfo.h + src/Bullet3Collision/NarrowPhaseCollision/b3RigidBodyCL.h src/Bullet3Collision/NarrowPhaseCollision/shared/b3BvhSubtreeInfoData.h - src/Bullet3Collision/NarrowPhaseCollision/shared/b3Contact4Data.h src/Bullet3Collision/NarrowPhaseCollision/shared/b3BvhTraversal.h + src/Bullet3Collision/NarrowPhaseCollision/shared/b3ClipFaces.h + src/Bullet3Collision/NarrowPhaseCollision/shared/b3Collidable.h + src/Bullet3Collision/NarrowPhaseCollision/shared/b3Contact4Data.h + src/Bullet3Collision/NarrowPhaseCollision/shared/b3ContactConvexConvexSAT.h + src/Bullet3Collision/NarrowPhaseCollision/shared/b3ContactSphereSphere.h src/Bullet3Collision/NarrowPhaseCollision/shared/b3ConvexPolyhedronData.h - src/Bullet3Collision/NarrowPhaseCollision/shared/b3NewContactReduction.h - src/Bullet3Collision/NarrowPhaseCollision/shared/b3RigidBodyData.h + src/Bullet3Collision/NarrowPhaseCollision/shared/b3FindConcaveSatAxis.h + src/Bullet3Collision/NarrowPhaseCollision/shared/b3FindSeparatingAxis.h src/Bullet3Collision/NarrowPhaseCollision/shared/b3MprPenetration.h - src/Bullet3Collision/NarrowPhaseCollision/shared/b3Collidable.h + src/Bullet3Collision/NarrowPhaseCollision/shared/b3NewContactReduction.h src/Bullet3Collision/NarrowPhaseCollision/shared/b3QuantizedBvhNodeData.h - src/Bullet3Collision/NarrowPhaseCollision/shared/b3ClipFaces.h - src/Bullet3Collision/NarrowPhaseCollision/shared/b3FindConcaveSatAxis.h - src/Bullet3Collision/NarrowPhaseCollision/shared/b3UpdateAabbs.h src/Bullet3Collision/NarrowPhaseCollision/shared/b3ReduceContacts.h - src/Bullet3Collision/NarrowPhaseCollision/shared/b3ContactSphereSphere.h - src/Bullet3Collision/NarrowPhaseCollision/shared/b3FindSeparatingAxis.h - src/Bullet3Collision/NarrowPhaseCollision/b3RaycastInfo.h - src/Bullet3Collision/NarrowPhaseCollision/b3CpuNarrowPhase.h - src/Bullet3Collision/NarrowPhaseCollision/b3Config.h - src/Bullet3Collision/NarrowPhaseCollision/b3Contact4.h - src/Bullet3Collision/NarrowPhaseCollision/b3RigidBodyCL.h - src/Bullet3Collision/NarrowPhaseCollision/b3ConvexUtility.h - src/Bullet3Collision/BroadPhaseCollision/shared/b3Aabb.h - src/Bullet3Collision/BroadPhaseCollision/b3BroadphaseCallback.h - src/Bullet3Collision/BroadPhaseCollision/b3DynamicBvhBroadphase.h - src/Bullet3Collision/BroadPhaseCollision/b3DynamicBvh.h - src/Bullet3Collision/BroadPhaseCollision/b3OverlappingPair.h - src/Bullet3Collision/BroadPhaseCollision/b3OverlappingPairCache.h - src/btBulletDynamicsCommon.h - src/Bullet3Serialize/Bullet2FileLoader/b3Defines.h - src/Bullet3Serialize/Bullet2FileLoader/autogenerated/bullet2.h - src/Bullet3Serialize/Bullet2FileLoader/b3File.h - src/Bullet3Serialize/Bullet2FileLoader/b3Chunk.h - src/Bullet3Serialize/Bullet2FileLoader/b3BulletFile.h - src/Bullet3Serialize/Bullet2FileLoader/b3DNA.h - src/Bullet3Serialize/Bullet2FileLoader/b3Serializer.h - src/Bullet3Serialize/Bullet2FileLoader/b3Common.h - src/Bullet3OpenCL/BroadphaseCollision/kernels/gridBroadphaseKernels.h - src/Bullet3OpenCL/BroadphaseCollision/kernels/sapKernels.h - src/Bullet3OpenCL/BroadphaseCollision/kernels/parallelLinearBvhKernels.h + src/Bullet3Collision/NarrowPhaseCollision/shared/b3RigidBodyData.h + src/Bullet3Collision/NarrowPhaseCollision/shared/b3UpdateAabbs.h + src/Bullet3Common/b3AlignedAllocator.h + src/Bullet3Common/b3AlignedObjectArray.h + src/Bullet3Common/b3CommandLineArgs.h + src/Bullet3Common/b3FileUtils.h + src/Bullet3Common/b3HashMap.h + src/Bullet3Common/b3Logging.h + src/Bullet3Common/b3Matrix3x3.h + src/Bullet3Common/b3MinMax.h + src/Bullet3Common/b3PoolAllocator.h + src/Bullet3Common/b3QuadWord.h + src/Bullet3Common/b3Quaternion.h + src/Bullet3Common/b3Random.h + src/Bullet3Common/b3ResizablePool.h + src/Bullet3Common/b3Scalar.h + src/Bullet3Common/b3StackAlloc.h + src/Bullet3Common/b3Transform.h + src/Bullet3Common/b3TransformUtil.h + src/Bullet3Common/b3Vector3.h + src/Bullet3Common/shared/b3Float4.h + src/Bullet3Common/shared/b3Int2.h + src/Bullet3Common/shared/b3Int4.h + src/Bullet3Common/shared/b3Mat3x3.h + src/Bullet3Common/shared/b3PlatformDefinitions.h + src/Bullet3Common/shared/b3Quat.h + src/Bullet3Dynamics/b3CpuRigidBodyPipeline.h + src/Bullet3Dynamics/ConstraintSolver/b3ContactSolverInfo.h + src/Bullet3Dynamics/ConstraintSolver/b3FixedConstraint.h + src/Bullet3Dynamics/ConstraintSolver/b3Generic6DofConstraint.h + src/Bullet3Dynamics/ConstraintSolver/b3JacobianEntry.h + src/Bullet3Dynamics/ConstraintSolver/b3PgsJacobiSolver.h + src/Bullet3Dynamics/ConstraintSolver/b3Point2PointConstraint.h + src/Bullet3Dynamics/ConstraintSolver/b3SolverBody.h + src/Bullet3Dynamics/ConstraintSolver/b3SolverConstraint.h + src/Bullet3Dynamics/ConstraintSolver/b3TypedConstraint.h + src/Bullet3Dynamics/shared/b3ContactConstraint4.h + src/Bullet3Dynamics/shared/b3ConvertConstraint4.h + src/Bullet3Dynamics/shared/b3Inertia.h + src/Bullet3Dynamics/shared/b3IntegrateTransforms.h + src/Bullet3Geometry/b3AabbUtil.h + src/Bullet3Geometry/b3ConvexHullComputer.h + src/Bullet3Geometry/b3GeometryUtil.h + src/Bullet3Geometry/b3GrahamScan2dConvexHull.h + src/Bullet3OpenCL/BroadphaseCollision/b3GpuBroadphaseInterface.h src/Bullet3OpenCL/BroadphaseCollision/b3GpuGridBroadphase.h - src/Bullet3OpenCL/BroadphaseCollision/b3GpuSapBroadphase.h src/Bullet3OpenCL/BroadphaseCollision/b3GpuParallelLinearBvhBroadphase.h src/Bullet3OpenCL/BroadphaseCollision/b3GpuParallelLinearBvh.h - src/Bullet3OpenCL/BroadphaseCollision/b3GpuBroadphaseInterface.h + src/Bullet3OpenCL/BroadphaseCollision/b3GpuSapBroadphase.h src/Bullet3OpenCL/BroadphaseCollision/b3SapAabb.h - src/Bullet3OpenCL/Raycast/kernels/rayCastKernels.h - src/Bullet3OpenCL/Raycast/b3GpuRaycast.h - src/Bullet3OpenCL/NarrowphaseCollision/b3ConvexPolyhedronCL.h - src/Bullet3OpenCL/NarrowphaseCollision/b3TriangleCallback.h - src/Bullet3OpenCL/NarrowphaseCollision/kernels/primitiveContacts.h - src/Bullet3OpenCL/NarrowphaseCollision/kernels/satKernels.h - src/Bullet3OpenCL/NarrowphaseCollision/kernels/satConcaveKernels.h - src/Bullet3OpenCL/NarrowphaseCollision/kernels/satClipHullContacts.h - src/Bullet3OpenCL/NarrowphaseCollision/kernels/mprKernels.h - src/Bullet3OpenCL/NarrowphaseCollision/kernels/bvhTraversal.h - src/Bullet3OpenCL/NarrowphaseCollision/b3VectorFloat4.h - src/Bullet3OpenCL/NarrowphaseCollision/b3StridingMeshInterface.h - src/Bullet3OpenCL/NarrowphaseCollision/b3TriangleIndexVertexArray.h + src/Bullet3OpenCL/BroadphaseCollision/kernels/gridBroadphaseKernels.h + src/Bullet3OpenCL/BroadphaseCollision/kernels/parallelLinearBvhKernels.h + src/Bullet3OpenCL/BroadphaseCollision/kernels/sapKernels.h + src/Bullet3OpenCL/Initialize/b3OpenCLInclude.h + src/Bullet3OpenCL/Initialize/b3OpenCLUtils.h + src/Bullet3OpenCL/NarrowphaseCollision/b3BvhInfo.h src/Bullet3OpenCL/NarrowphaseCollision/b3ContactCache.h - src/Bullet3OpenCL/NarrowphaseCollision/b3VoronoiSimplexSolver.h src/Bullet3OpenCL/NarrowphaseCollision/b3ConvexHullContact.h - src/Bullet3OpenCL/NarrowphaseCollision/b3BvhInfo.h + src/Bullet3OpenCL/NarrowphaseCollision/b3ConvexPolyhedronCL.h + src/Bullet3OpenCL/NarrowphaseCollision/b3GjkEpa.h src/Bullet3OpenCL/NarrowphaseCollision/b3OptimizedBvh.h - src/Bullet3OpenCL/NarrowphaseCollision/b3SupportMappings.h src/Bullet3OpenCL/NarrowphaseCollision/b3QuantizedBvh.h - src/Bullet3OpenCL/NarrowphaseCollision/b3GjkEpa.h - src/Bullet3OpenCL/ParallelPrimitives/b3FillCL.h + src/Bullet3OpenCL/NarrowphaseCollision/b3StridingMeshInterface.h + src/Bullet3OpenCL/NarrowphaseCollision/b3SupportMappings.h + src/Bullet3OpenCL/NarrowphaseCollision/b3TriangleCallback.h + src/Bullet3OpenCL/NarrowphaseCollision/b3TriangleIndexVertexArray.h + src/Bullet3OpenCL/NarrowphaseCollision/b3VectorFloat4.h + src/Bullet3OpenCL/NarrowphaseCollision/b3VoronoiSimplexSolver.h + src/Bullet3OpenCL/NarrowphaseCollision/kernels/bvhTraversal.h + src/Bullet3OpenCL/NarrowphaseCollision/kernels/mprKernels.h + src/Bullet3OpenCL/NarrowphaseCollision/kernels/primitiveContacts.h + src/Bullet3OpenCL/NarrowphaseCollision/kernels/satClipHullContacts.h + src/Bullet3OpenCL/NarrowphaseCollision/kernels/satConcaveKernels.h + src/Bullet3OpenCL/NarrowphaseCollision/kernels/satKernels.h + src/Bullet3OpenCL/ParallelPrimitives/b3BoundSearchCL.h src/Bullet3OpenCL/ParallelPrimitives/b3BufferInfoCL.h - src/Bullet3OpenCL/ParallelPrimitives/kernels/RadixSort32KernelsCL.h - src/Bullet3OpenCL/ParallelPrimitives/kernels/CopyKernelsCL.h - src/Bullet3OpenCL/ParallelPrimitives/kernels/PrefixScanKernelsFloat4CL.h - src/Bullet3OpenCL/ParallelPrimitives/kernels/FillKernelsCL.h - src/Bullet3OpenCL/ParallelPrimitives/kernels/BoundSearchKernelsCL.h - src/Bullet3OpenCL/ParallelPrimitives/kernels/PrefixScanKernelsCL.h + src/Bullet3OpenCL/ParallelPrimitives/b3FillCL.h + src/Bullet3OpenCL/ParallelPrimitives/b3LauncherCL.h src/Bullet3OpenCL/ParallelPrimitives/b3OpenCLArray.h + src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanCL.h src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanFloat4CL.h - src/Bullet3OpenCL/ParallelPrimitives/b3LauncherCL.h src/Bullet3OpenCL/ParallelPrimitives/b3RadixSort32CL.h - src/Bullet3OpenCL/ParallelPrimitives/b3BoundSearchCL.h - src/Bullet3OpenCL/ParallelPrimitives/b3PrefixScanCL.h - src/Bullet3OpenCL/Initialize/b3OpenCLUtils.h - src/Bullet3OpenCL/Initialize/b3OpenCLInclude.h - src/Bullet3OpenCL/RigidBody/b3GpuSolverConstraint.h - src/Bullet3OpenCL/RigidBody/b3GpuSolverBody.h + src/Bullet3OpenCL/ParallelPrimitives/kernels/BoundSearchKernelsCL.h + src/Bullet3OpenCL/ParallelPrimitives/kernels/CopyKernelsCL.h + src/Bullet3OpenCL/ParallelPrimitives/kernels/FillKernelsCL.h + src/Bullet3OpenCL/ParallelPrimitives/kernels/PrefixScanKernelsCL.h + src/Bullet3OpenCL/ParallelPrimitives/kernels/PrefixScanKernelsFloat4CL.h + src/Bullet3OpenCL/ParallelPrimitives/kernels/RadixSort32KernelsCL.h + src/Bullet3OpenCL/Raycast/b3GpuRaycast.h + src/Bullet3OpenCL/Raycast/kernels/rayCastKernels.h + src/Bullet3OpenCL/RigidBody/b3GpuConstraint4.h + src/Bullet3OpenCL/RigidBody/b3GpuGenericConstraint.h + src/Bullet3OpenCL/RigidBody/b3GpuJacobiContactSolver.h src/Bullet3OpenCL/RigidBody/b3GpuNarrowPhase.h + src/Bullet3OpenCL/RigidBody/b3GpuNarrowPhaseInternalData.h + src/Bullet3OpenCL/RigidBody/b3GpuPgsConstraintSolver.h + src/Bullet3OpenCL/RigidBody/b3GpuPgsContactSolver.h + src/Bullet3OpenCL/RigidBody/b3GpuRigidBodyPipeline.h + src/Bullet3OpenCL/RigidBody/b3GpuRigidBodyPipelineInternalData.h + src/Bullet3OpenCL/RigidBody/b3GpuSolverBody.h + src/Bullet3OpenCL/RigidBody/b3GpuSolverConstraint.h + src/Bullet3OpenCL/RigidBody/b3Solver.h + src/Bullet3OpenCL/RigidBody/kernels/batchingKernels.h + src/Bullet3OpenCL/RigidBody/kernels/batchingKernelsNew.h + src/Bullet3OpenCL/RigidBody/kernels/integrateKernel.h src/Bullet3OpenCL/RigidBody/kernels/jointSolver.h + src/Bullet3OpenCL/RigidBody/kernels/solveContact.h + src/Bullet3OpenCL/RigidBody/kernels/solveFriction.h src/Bullet3OpenCL/RigidBody/kernels/solverSetup2.h - src/Bullet3OpenCL/RigidBody/kernels/solverUtils.h src/Bullet3OpenCL/RigidBody/kernels/solverSetup.h + src/Bullet3OpenCL/RigidBody/kernels/solverUtils.h src/Bullet3OpenCL/RigidBody/kernels/updateAabbsKernel.h - src/Bullet3OpenCL/RigidBody/kernels/solveContact.h - src/Bullet3OpenCL/RigidBody/kernels/solveFriction.h - src/Bullet3OpenCL/RigidBody/kernels/integrateKernel.h - src/Bullet3OpenCL/RigidBody/kernels/batchingKernelsNew.h - src/Bullet3OpenCL/RigidBody/kernels/batchingKernels.h - src/Bullet3OpenCL/RigidBody/b3GpuPgsContactSolver.h - src/Bullet3OpenCL/RigidBody/b3GpuPgsConstraintSolver.h - src/Bullet3OpenCL/RigidBody/b3GpuJacobiContactSolver.h - src/Bullet3OpenCL/RigidBody/b3GpuGenericConstraint.h - src/Bullet3OpenCL/RigidBody/b3GpuNarrowPhaseInternalData.h - src/Bullet3OpenCL/RigidBody/b3GpuConstraint4.h - src/Bullet3OpenCL/RigidBody/b3GpuRigidBodyPipeline.h - src/Bullet3OpenCL/RigidBody/b3Solver.h - src/Bullet3OpenCL/RigidBody/b3GpuRigidBodyPipelineInternalData.h - src/LinearMath/btMinMax.h - src/LinearMath/btQuaternion.h - src/LinearMath/btTransform.h - src/LinearMath/btStackAlloc.h - src/LinearMath/btPolarDecomposition.h - src/LinearMath/TaskScheduler/btThreadSupportInterface.h - src/LinearMath/btAabbUtil2.h - src/LinearMath/btDefaultMotionState.h - src/LinearMath/btSpatialAlgebra.h - src/LinearMath/btHashMap.h - src/LinearMath/btMotionState.h - src/LinearMath/btAlignedObjectArray.h - src/LinearMath/btConvexHull.h - src/LinearMath/btIDebugDraw.h - src/LinearMath/btList.h - src/LinearMath/btPoolAllocator.h - src/LinearMath/btCpuFeatureUtility.h - src/LinearMath/btMatrix3x3.h - src/LinearMath/btGrahamScan2dConvexHull.h - src/LinearMath/btGeometryUtil.h - src/LinearMath/btVector3.h - src/LinearMath/btTransformUtil.h - src/LinearMath/btRandom.h - src/LinearMath/btSerializer.h - src/LinearMath/btAlignedAllocator.h - src/LinearMath/btScalar.h - src/LinearMath/btQuadWord.h - src/LinearMath/btMatrixX.h - src/LinearMath/btQuickprof.h - src/LinearMath/btConvexHullComputer.h - src/LinearMath/btThreads.h - src/Bullet3Dynamics/shared/b3Inertia.h - src/Bullet3Dynamics/shared/b3ConvertConstraint4.h - src/Bullet3Dynamics/shared/b3IntegrateTransforms.h - src/Bullet3Dynamics/shared/b3ContactConstraint4.h - src/Bullet3Dynamics/b3CpuRigidBodyPipeline.h - src/Bullet3Dynamics/ConstraintSolver/b3Generic6DofConstraint.h - src/Bullet3Dynamics/ConstraintSolver/b3SolverConstraint.h - src/Bullet3Dynamics/ConstraintSolver/b3JacobianEntry.h - src/Bullet3Dynamics/ConstraintSolver/b3FixedConstraint.h - src/Bullet3Dynamics/ConstraintSolver/b3TypedConstraint.h - src/Bullet3Dynamics/ConstraintSolver/b3PgsJacobiSolver.h - src/Bullet3Dynamics/ConstraintSolver/b3Point2PointConstraint.h - src/Bullet3Dynamics/ConstraintSolver/b3SolverBody.h - src/Bullet3Dynamics/ConstraintSolver/b3ContactSolverInfo.h - src/BulletCollision/BroadphaseCollision/btOverlappingPairCallback.h + src/Bullet3Serialize/Bullet2FileLoader/autogenerated/bullet2.h + src/Bullet3Serialize/Bullet2FileLoader/b3BulletFile.h + src/Bullet3Serialize/Bullet2FileLoader/b3Chunk.h + src/Bullet3Serialize/Bullet2FileLoader/b3Common.h + src/Bullet3Serialize/Bullet2FileLoader/b3Defines.h + src/Bullet3Serialize/Bullet2FileLoader/b3DNA.h + src/Bullet3Serialize/Bullet2FileLoader/b3File.h + src/Bullet3Serialize/Bullet2FileLoader/b3Serializer.h + src/Bullet-C-Api.h src/BulletCollision/BroadphaseCollision/btAxisSweep3.h src/BulletCollision/BroadphaseCollision/btAxisSweep3Internal.h - src/BulletCollision/BroadphaseCollision/btDbvt.h - src/BulletCollision/BroadphaseCollision/btDispatcher.h - src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.h - src/BulletCollision/BroadphaseCollision/btCollisionAlgorithm.h - src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.h src/BulletCollision/BroadphaseCollision/btBroadphaseInterface.h - src/BulletCollision/BroadphaseCollision/btQuantizedBvh.h + src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.h + src/BulletCollision/BroadphaseCollision/btCollisionAlgorithm.h src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.h + src/BulletCollision/BroadphaseCollision/btDbvt.h + src/BulletCollision/BroadphaseCollision/btDispatcher.h src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h - src/BulletCollision/CollisionDispatch/btManifoldResult.h - src/BulletCollision/CollisionDispatch/btConvexPlaneCollisionAlgorithm.h - src/BulletCollision/CollisionDispatch/btUnionFind.h - src/BulletCollision/CollisionDispatch/btSphereBoxCollisionAlgorithm.h - src/BulletCollision/CollisionDispatch/btGhostObject.h + src/BulletCollision/BroadphaseCollision/btOverlappingPairCallback.h + src/BulletCollision/BroadphaseCollision/btQuantizedBvh.h + src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.h + src/BulletCollision/CollisionDispatch/btActivatingCollisionAlgorithm.h + src/BulletCollision/CollisionDispatch/btBox2dBox2dCollisionAlgorithm.h + src/BulletCollision/CollisionDispatch/btBoxBoxCollisionAlgorithm.h + src/BulletCollision/CollisionDispatch/btBoxBoxDetector.h + src/BulletCollision/CollisionDispatch/btCollisionConfiguration.h src/BulletCollision/CollisionDispatch/btCollisionCreateFunc.h - src/BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.h - src/BulletCollision/CollisionDispatch/btConvex2dConvex2dAlgorithm.h + src/BulletCollision/CollisionDispatch/btCollisionDispatcher.h + src/BulletCollision/CollisionDispatch/btCollisionDispatcherMt.h src/BulletCollision/CollisionDispatch/btCollisionObject.h - src/BulletCollision/CollisionDispatch/btInternalEdgeUtility.h + src/BulletCollision/CollisionDispatch/btCollisionObjectWrapper.h + src/BulletCollision/CollisionDispatch/btCollisionWorld.h src/BulletCollision/CollisionDispatch/btCollisionWorldImporter.h - src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.h - src/BulletCollision/CollisionDispatch/btCollisionDispatcherMt.h - src/BulletCollision/CollisionDispatch/btSphereTriangleCollisionAlgorithm.h - src/BulletCollision/CollisionDispatch/btSphereSphereCollisionAlgorithm.h - src/BulletCollision/CollisionDispatch/btBoxBoxCollisionAlgorithm.h src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.h + src/BulletCollision/CollisionDispatch/btCompoundCompoundCollisionAlgorithm.h + src/BulletCollision/CollisionDispatch/btConvex2dConvex2dAlgorithm.h + src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.h + src/BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.h + src/BulletCollision/CollisionDispatch/btConvexPlaneCollisionAlgorithm.h + src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h + src/BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.h + src/BulletCollision/CollisionDispatch/btGhostObject.h + src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.h + src/BulletCollision/CollisionDispatch/btInternalEdgeUtility.h + src/BulletCollision/CollisionDispatch/btManifoldResult.h src/BulletCollision/CollisionDispatch/btSimulationIslandManager.h + src/BulletCollision/CollisionDispatch/btSphereBoxCollisionAlgorithm.h + src/BulletCollision/CollisionDispatch/btSphereSphereCollisionAlgorithm.h + src/BulletCollision/CollisionDispatch/btSphereTriangleCollisionAlgorithm.h + src/BulletCollision/CollisionDispatch/btUnionFind.h src/BulletCollision/CollisionDispatch/SphereTriangleDetector.h - src/BulletCollision/CollisionDispatch/btCollisionDispatcher.h - src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h - src/BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.h - src/BulletCollision/CollisionDispatch/btCompoundCompoundCollisionAlgorithm.h - src/BulletCollision/CollisionDispatch/btCollisionObjectWrapper.h - src/BulletCollision/CollisionDispatch/btBox2dBox2dCollisionAlgorithm.h - src/BulletCollision/CollisionDispatch/btActivatingCollisionAlgorithm.h - src/BulletCollision/CollisionDispatch/btCollisionWorld.h - src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.h - src/BulletCollision/CollisionDispatch/btBoxBoxDetector.h - src/BulletCollision/CollisionDispatch/btCollisionConfiguration.h - src/BulletCollision/CollisionShapes/btTriangleMeshShape.h - src/BulletCollision/CollisionShapes/btStaticPlaneShape.h - src/BulletCollision/CollisionShapes/btHeightfieldTerrainShape.h + src/BulletCollision/CollisionShapes/btBox2dShape.h + src/BulletCollision/CollisionShapes/btBoxShape.h src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.h - src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.h - src/BulletCollision/CollisionShapes/btCollisionMargin.h - src/BulletCollision/CollisionShapes/btSphereShape.h - src/BulletCollision/CollisionShapes/btTriangleShape.h src/BulletCollision/CollisionShapes/btCapsuleShape.h - src/BulletCollision/CollisionShapes/btConvexShape.h - src/BulletCollision/CollisionShapes/btBoxShape.h - src/BulletCollision/CollisionShapes/btTriangleCallback.h - src/BulletCollision/CollisionShapes/btConvexPolyhedron.h - src/BulletCollision/CollisionShapes/btTriangleIndexVertexMaterialArray.h - src/BulletCollision/CollisionShapes/btConeShape.h - src/BulletCollision/CollisionShapes/btCylinderShape.h - src/BulletCollision/CollisionShapes/btMinkowskiSumShape.h - src/BulletCollision/CollisionShapes/btScaledBvhTriangleMeshShape.h - src/BulletCollision/CollisionShapes/btTriangleInfoMap.h - src/BulletCollision/CollisionShapes/btEmptyShape.h - src/BulletCollision/CollisionShapes/btSdfCollisionShape.h - src/BulletCollision/CollisionShapes/btTriangleMesh.h - src/BulletCollision/CollisionShapes/btUniformScalingShape.h - src/BulletCollision/CollisionShapes/btTriangleBuffer.h - src/BulletCollision/CollisionShapes/btConcaveShape.h - src/BulletCollision/CollisionShapes/btBox2dShape.h + src/BulletCollision/CollisionShapes/btCollisionMargin.h src/BulletCollision/CollisionShapes/btCollisionShape.h - src/BulletCollision/CollisionShapes/btMiniSDF.h - src/BulletCollision/CollisionShapes/btConvexPointCloudShape.h + src/BulletCollision/CollisionShapes/btCompoundShape.h + src/BulletCollision/CollisionShapes/btConcaveShape.h + src/BulletCollision/CollisionShapes/btConeShape.h + src/BulletCollision/CollisionShapes/btConvex2dShape.h + src/BulletCollision/CollisionShapes/btConvexHullShape.h src/BulletCollision/CollisionShapes/btConvexInternalShape.h + src/BulletCollision/CollisionShapes/btConvexPointCloudShape.h + src/BulletCollision/CollisionShapes/btConvexPolyhedron.h + src/BulletCollision/CollisionShapes/btConvexShape.h src/BulletCollision/CollisionShapes/btConvexTriangleMeshShape.h - src/BulletCollision/CollisionShapes/btStridingMeshInterface.h - src/BulletCollision/CollisionShapes/btMultiSphereShape.h + src/BulletCollision/CollisionShapes/btCylinderShape.h + src/BulletCollision/CollisionShapes/btEmptyShape.h + src/BulletCollision/CollisionShapes/btHeightfieldTerrainShape.h + src/BulletCollision/CollisionShapes/btMaterial.h + src/BulletCollision/CollisionShapes/btMinkowskiSumShape.h src/BulletCollision/CollisionShapes/btMultimaterialTriangleMeshShape.h + src/BulletCollision/CollisionShapes/btMultiSphereShape.h src/BulletCollision/CollisionShapes/btOptimizedBvh.h - src/BulletCollision/CollisionShapes/btTetrahedronShape.h + src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.h + src/BulletCollision/CollisionShapes/btScaledBvhTriangleMeshShape.h src/BulletCollision/CollisionShapes/btShapeHull.h + src/BulletCollision/CollisionShapes/btSphereShape.h + src/BulletCollision/CollisionShapes/btStaticPlaneShape.h + src/BulletCollision/CollisionShapes/btStridingMeshInterface.h + src/BulletCollision/CollisionShapes/btTetrahedronShape.h + src/BulletCollision/CollisionShapes/btTriangleBuffer.h + src/BulletCollision/CollisionShapes/btTriangleCallback.h src/BulletCollision/CollisionShapes/btTriangleIndexVertexArray.h - src/BulletCollision/CollisionShapes/btConvexHullShape.h - src/BulletCollision/CollisionShapes/btCompoundShape.h - src/BulletCollision/CollisionShapes/btConvex2dShape.h - src/BulletCollision/CollisionShapes/btMaterial.h - src/BulletCollision/Gimpact/btGeometryOperations.h - src/BulletCollision/Gimpact/gim_geometry.h - src/BulletCollision/Gimpact/gim_math.h - src/BulletCollision/Gimpact/gim_tri_collision.h - src/BulletCollision/Gimpact/btGImpactCollisionAlgorithm.h - src/BulletCollision/Gimpact/gim_hash_table.h - src/BulletCollision/Gimpact/gim_array.h + src/BulletCollision/CollisionShapes/btTriangleIndexVertexMaterialArray.h + src/BulletCollision/CollisionShapes/btTriangleInfoMap.h + src/BulletCollision/CollisionShapes/btTriangleMesh.h + src/BulletCollision/CollisionShapes/btTriangleMeshShape.h + src/BulletCollision/CollisionShapes/btTriangleShape.h + src/BulletCollision/CollisionShapes/btUniformScalingShape.h src/BulletCollision/Gimpact/btBoxCollision.h - src/BulletCollision/Gimpact/btGImpactQuantizedBvhStructs.h - src/BulletCollision/Gimpact/gim_box_set.h - src/BulletCollision/Gimpact/gim_contact.h - src/BulletCollision/Gimpact/gim_basic_geometry_operations.h - src/BulletCollision/Gimpact/btGImpactShape.h - src/BulletCollision/Gimpact/btGenericPoolAllocator.h - src/BulletCollision/Gimpact/gim_bitset.h - src/BulletCollision/Gimpact/gim_clip_polygon.h - src/BulletCollision/Gimpact/btGImpactMassUtil.h + src/BulletCollision/Gimpact/btClipPolygon.h src/BulletCollision/Gimpact/btCompoundFromGimpact.h + src/BulletCollision/Gimpact/btContactProcessing.h src/BulletCollision/Gimpact/btContactProcessingStructs.h - src/BulletCollision/Gimpact/gim_geom_types.h - src/BulletCollision/Gimpact/gim_box_collision.h + src/BulletCollision/Gimpact/btGenericPoolAllocator.h + src/BulletCollision/Gimpact/btGeometryOperations.h src/BulletCollision/Gimpact/btGImpactBvh.h - src/BulletCollision/Gimpact/gim_radixsort.h - src/BulletCollision/Gimpact/btQuantization.h src/BulletCollision/Gimpact/btGImpactBvhStructs.h - src/BulletCollision/Gimpact/btClipPolygon.h + src/BulletCollision/Gimpact/btGImpactCollisionAlgorithm.h + src/BulletCollision/Gimpact/btGImpactMassUtil.h src/BulletCollision/Gimpact/btGImpactQuantizedBvh.h - src/BulletCollision/Gimpact/gim_memory.h + src/BulletCollision/Gimpact/btGImpactQuantizedBvhStructs.h + src/BulletCollision/Gimpact/btGImpactShape.h + src/BulletCollision/Gimpact/btQuantization.h src/BulletCollision/Gimpact/btTriangleShapeEx.h - src/BulletCollision/Gimpact/btContactProcessing.h + src/BulletCollision/Gimpact/gim_array.h + src/BulletCollision/Gimpact/gim_basic_geometry_operations.h + src/BulletCollision/Gimpact/gim_bitset.h + src/BulletCollision/Gimpact/gim_box_collision.h + src/BulletCollision/Gimpact/gim_box_set.h + src/BulletCollision/Gimpact/gim_clip_polygon.h + src/BulletCollision/Gimpact/gim_contact.h + src/BulletCollision/Gimpact/gim_geometry.h + src/BulletCollision/Gimpact/gim_geom_types.h + src/BulletCollision/Gimpact/gim_hash_table.h src/BulletCollision/Gimpact/gim_linear_math.h - src/BulletCollision/NarrowPhaseCollision/btGjkConvexCast.h - src/BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.h + src/BulletCollision/Gimpact/gim_math.h + src/BulletCollision/Gimpact/gim_memory.h + src/BulletCollision/Gimpact/gim_radixsort.h + src/BulletCollision/Gimpact/gim_tri_collision.h + src/BulletCollision/NarrowPhaseCollision/btComputeGjkEpaPenetration.h + src/BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.h src/BulletCollision/NarrowPhaseCollision/btConvexCast.h - src/BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.h src/BulletCollision/NarrowPhaseCollision/btConvexPenetrationDepthSolver.h - src/BulletCollision/NarrowPhaseCollision/btMprPenetration.h + src/BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h + src/BulletCollision/NarrowPhaseCollision/btGjkCollisionDescription.h + src/BulletCollision/NarrowPhaseCollision/btGjkConvexCast.h + src/BulletCollision/NarrowPhaseCollision/btGjkEpa2.h + src/BulletCollision/NarrowPhaseCollision/btGjkEpa3.h + src/BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.h src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.h - src/BulletCollision/NarrowPhaseCollision/btPolyhedralContactClipping.h + src/BulletCollision/NarrowPhaseCollision/btManifoldPoint.h + src/BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.h + src/BulletCollision/NarrowPhaseCollision/btMprPenetration.h + src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.h src/BulletCollision/NarrowPhaseCollision/btPointCollector.h + src/BulletCollision/NarrowPhaseCollision/btPolyhedralContactClipping.h + src/BulletCollision/NarrowPhaseCollision/btRaycastCallback.h src/BulletCollision/NarrowPhaseCollision/btSimplexSolverInterface.h - src/BulletCollision/NarrowPhaseCollision/btManifoldPoint.h + src/BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.h src/BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h - src/BulletCollision/NarrowPhaseCollision/btRaycastCallback.h - src/BulletCollision/NarrowPhaseCollision/btGjkEpa2.h - src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.h - src/BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.h - src/BulletCollision/NarrowPhaseCollision/btGjkEpa3.h - src/BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h - src/BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.h - src/BulletCollision/NarrowPhaseCollision/btComputeGjkEpaPenetration.h - src/BulletCollision/NarrowPhaseCollision/btGjkCollisionDescription.h - src/Bullet-C-Api.h - src/Extras/ConvexDecomposition/bestfit.h - src/Extras/ConvexDecomposition/bestfitobb.h - src/Extras/ConvexDecomposition/cd_hull.h - src/Extras/ConvexDecomposition/cd_vector.h - src/Extras/ConvexDecomposition/cd_wavefront.h - src/Extras/ConvexDecomposition/concavity.h - src/Extras/ConvexDecomposition/ConvexBuilder.h - src/Extras/ConvexDecomposition/ConvexDecomposition.h - src/Extras/ConvexDecomposition/fitsphere.h - src/Extras/ConvexDecomposition/float_math.h - src/Extras/ConvexDecomposition/meshvolume.h - src/Extras/ConvexDecomposition/planetri.h - src/Extras/ConvexDecomposition/raytri.h - src/Extras/ConvexDecomposition/splitplane.h - src/Extras/ConvexDecomposition/vlookup.h - src/Extras/GIMPACTUtils/btGImpactConvexDecompositionShape.h - src/Extras/HACD/hacdCircularList.h - src/Extras/HACD/hacdGraph.h - src/Extras/HACD/hacdHACD.h - src/Extras/HACD/hacdICHull.h - src/Extras/HACD/hacdManifoldMesh.h - src/Extras/HACD/hacdVector.h - src/Extras/HACD/hacdVersion.h - src/Extras/InverseDynamics/BulletInverseDynamicsUtilsCommon.h - src/Extras/VHACD/inc/btConvexHullComputer.h - src/Extras/VHACD/inc/btMinMax.h - src/Extras/VHACD/inc/btScalar.h - src/Extras/VHACD/inc/btVector3.h - src/Extras/VHACD/inc/vhacdCircularList.h - src/Extras/VHACD/inc/vhacdICHull.h - src/Extras/VHACD/inc/vhacdManifoldMesh.h - src/Extras/VHACD/inc/vhacdMesh.h - src/Extras/VHACD/inc/vhacdMutex.h - src/Extras/VHACD/inc/vhacdSArray.h - src/Extras/VHACD/inc/vhacdTimer.h - src/Extras/VHACD/inc/vhacdVector.h - src/Extras/VHACD/inc/vhacdVHACD.h - src/Extras/VHACD/inc/vhacdVolume.h - src/Extras/VHACD/public/VHACD.h + src/BulletDynamics/Character/btCharacterControllerInterface.h + src/BulletDynamics/Character/btKinematicCharacterController.h + src/BulletDynamics/ConstraintSolver/btConeTwistConstraint.h + src/BulletDynamics/ConstraintSolver/btConstraintSolver.h + src/BulletDynamics/ConstraintSolver/btContactConstraint.h + src/BulletDynamics/ConstraintSolver/btContactSolverInfo.h + src/BulletDynamics/ConstraintSolver/btFixedConstraint.h + src/BulletDynamics/ConstraintSolver/btGearConstraint.h + src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.h + src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.h + src/BulletDynamics/ConstraintSolver/btGeneric6DofSpringConstraint.h + src/BulletDynamics/ConstraintSolver/btHinge2Constraint.h + src/BulletDynamics/ConstraintSolver/btHingeConstraint.h + src/BulletDynamics/ConstraintSolver/btJacobianEntry.h + src/BulletDynamics/ConstraintSolver/btNNCGConstraintSolver.h + src/BulletDynamics/ConstraintSolver/btPoint2PointConstraint.h + src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h + src/BulletDynamics/ConstraintSolver/btSliderConstraint.h + src/BulletDynamics/ConstraintSolver/btSolve2LinearConstraint.h + src/BulletDynamics/ConstraintSolver/btSolverBody.h + src/BulletDynamics/ConstraintSolver/btSolverConstraint.h + src/BulletDynamics/ConstraintSolver/btTypedConstraint.h + src/BulletDynamics/ConstraintSolver/btUniversalConstraint.h + src/BulletDynamics/Dynamics/btActionInterface.h + src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h + src/BulletDynamics/Dynamics/btDiscreteDynamicsWorldMt.h + src/BulletDynamics/Dynamics/btDynamicsWorld.h + src/BulletDynamics/Dynamics/btRigidBody.h + src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.h + src/BulletDynamics/Dynamics/btSimulationIslandManagerMt.h + src/BulletDynamics/Featherstone/btMultiBodyConstraint.h + src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h + src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h + src/BulletDynamics/Featherstone/btMultiBodyFixedConstraint.h + src/BulletDynamics/Featherstone/btMultiBodyGearConstraint.h + src/BulletDynamics/Featherstone/btMultiBody.h + src/BulletDynamics/Featherstone/btMultiBodyJointFeedback.h + src/BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.h + src/BulletDynamics/Featherstone/btMultiBodyJointMotor.h + src/BulletDynamics/Featherstone/btMultiBodyLinkCollider.h + src/BulletDynamics/Featherstone/btMultiBodyLink.h + src/BulletDynamics/Featherstone/btMultiBodyPoint2Point.h + src/BulletDynamics/Featherstone/btMultiBodySliderConstraint.h + src/BulletDynamics/Featherstone/btMultiBodySolverConstraint.h + src/BulletDynamics/MLCPSolvers/btDantzigLCP.h + src/BulletDynamics/MLCPSolvers/btDantzigSolver.h + src/BulletDynamics/MLCPSolvers/btLemkeAlgorithm.h + src/BulletDynamics/MLCPSolvers/btLemkeSolver.h + src/BulletDynamics/MLCPSolvers/btMLCPSolver.h + src/BulletDynamics/MLCPSolvers/btMLCPSolverInterface.h + src/BulletDynamics/MLCPSolvers/btPATHSolver.h + src/BulletDynamics/MLCPSolvers/btSolveProjectedGaussSeidel.h + src/BulletDynamics/Vehicle/btRaycastVehicle.h + src/BulletDynamics/Vehicle/btVehicleRaycaster.h + src/BulletDynamics/Vehicle/btWheelInfo.h + src/BulletSoftBody/btDefaultSoftBodySolver.h + src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.h + src/BulletSoftBody/btSoftBodyData.h + src/BulletSoftBody/btSoftBody.h + src/BulletSoftBody/btSoftBodyHelpers.h + src/BulletSoftBody/btSoftBodyInternals.h + src/BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h + src/BulletSoftBody/btSoftBodySolvers.h + src/BulletSoftBody/btSoftBodySolverVertexBuffer.h + src/BulletSoftBody/btSoftMultiBodyDynamicsWorld.h + src/BulletSoftBody/btSoftRigidCollisionAlgorithm.h + src/BulletSoftBody/btSoftRigidDynamicsWorld.h + src/BulletSoftBody/btSoftRigidDynamicsWorldMt.h + src/BulletSoftBody/btSoftSoftCollisionAlgorithm.h + src/BulletSoftBody/btSparseSDF.h + src/clew/clew.h + src/LinearMath/btAabbUtil2.h + src/LinearMath/btAlignedAllocator.h + src/LinearMath/btAlignedObjectArray.h + src/LinearMath/btConvexHullComputer.h + src/LinearMath/btConvexHull.h + src/LinearMath/btCpuFeatureUtility.h + src/LinearMath/btDefaultMotionState.h + src/LinearMath/btGeometryUtil.h + src/LinearMath/btGrahamScan2dConvexHull.h + src/LinearMath/btHashMap.h + src/LinearMath/btIDebugDraw.h + src/LinearMath/btList.h + src/LinearMath/btMatrix3x3.h + src/LinearMath/btMatrixX.h + src/LinearMath/btMinMax.h + src/LinearMath/btMotionState.h + src/LinearMath/btPolarDecomposition.h + src/LinearMath/btPoolAllocator.h + src/LinearMath/btQuadWord.h + src/LinearMath/btQuaternion.h + src/LinearMath/btQuickprof.h + src/LinearMath/btRandom.h + src/LinearMath/btScalar.h + src/LinearMath/btSerializer.h + src/LinearMath/btSpatialAlgebra.h + src/LinearMath/btStackAlloc.h + src/LinearMath/btThreads.h + src/LinearMath/btTransform.h + src/LinearMath/btTransformUtil.h + src/LinearMath/btVector3.h ) add_definitions( diff --git a/extern/bullet/patches/blender.patch b/extern/bullet/patches/blender.patch index 5dfc704003d5..346b870320f7 100644 --- a/extern/bullet/patches/blender.patch +++ b/extern/bullet/patches/blender.patch @@ -1,36 +1,223 @@ -diff --git a/extern/bullet/src/LinearMath/btScalar.h b/extern/bullet/src/LinearMath/btScalar.h ---- a/extern/bullet/src/LinearMath/btScalar.h -+++ b/extern/bullet/src/LinearMath/btScalar.h -@@ -16,6 +16,9 @@ - - #ifndef BT_SCALAR_H - #define BT_SCALAR_H -+#if defined(_MSC_VER) && defined(__clang__) /* clang supplies it's own overloads already */ -+#define BT_NO_SIMD_OPERATOR_OVERLOADS +From 82c5544df857605aef7fb1b8b85da5b9f41044ef Mon Sep 17 00:00:00 2001 +From: tristan +Date: Fri, 12 Oct 2018 13:16:12 +0200 +Subject: [PATCH] temp + +temp +--- + extern/bullet/src/Bullet-C-Api.h | 187 +++++++ + .../CollisionDispatch/btCollisionWorld.h | 2 +- + .../CollisionShapes/btConvexHullShape.cpp | 6 +- + .../CollisionShapes/btConvexShape.cpp | 6 +- + .../CollisionShapes/btMultiSphereShape.cpp | 6 +- + .../btPolyhedralConvexShape.cpp | 6 +- + .../ConstraintSolver/btSolverBody.h | 7 +- + .../BulletDynamics/Dynamics/Bullet-C-API.cpp | 469 ++++++++++++++++++ + .../BulletDynamics/Dynamics/btRigidBody.cpp | 54 +- + .../src/BulletDynamics/Dynamics/btRigidBody.h | 2 + + .../src/LinearMath/btConvexHullComputer.cpp | 2 + + .../src/LinearMath/btConvexHullComputer.h | 1 + + extern/bullet/src/LinearMath/btScalar.h | 5 +- + extern/bullet/src/LinearMath/btVector3.cpp | 6 +- + 14 files changed, 708 insertions(+), 51 deletions(-) + create mode 100644 extern/bullet/src/Bullet-C-Api.h + create mode 100644 extern/bullet/src/BulletDynamics/Dynamics/Bullet-C-API.cpp + +diff --git a/extern/bullet/src/Bullet-C-Api.h b/extern/bullet/src/Bullet-C-Api.h +new file mode 100644 +index 00000000000..5d00f7e3ac3 +--- /dev/null ++++ b/extern/bullet/src/Bullet-C-Api.h +@@ -0,0 +1,187 @@ ++/* ++Bullet Continuous Collision Detection and Physics Library ++Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ ++ ++This software is provided 'as-is', without any express or implied warranty. ++In no event will the authors be held liable for any damages arising from the use of this software. ++Permission is granted to anyone to use this software for any purpose, ++including commercial applications, and to alter it and redistribute it freely, ++subject to the following restrictions: ++ ++1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. ++2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. ++3. This notice may not be removed or altered from any source distribution. ++*/ ++ ++/* ++ Draft high-level generic physics C-API. For low-level access, use the physics SDK native API's. ++ Work in progress, functionality will be added on demand. ++ ++ If possible, use the richer Bullet C++ API, by including "btBulletDynamicsCommon.h" ++*/ ++ ++#ifndef BULLET_C_API_H ++#define BULLET_C_API_H ++ ++#define PL_DECLARE_HANDLE(name) typedef struct name##__ { int unused; } *name ++ ++#ifdef BT_USE_DOUBLE_PRECISION ++typedef double plReal; ++#else ++typedef float plReal; +#endif - - #ifdef BT_MANAGED_CODE - //Aligned data types not supported in managed code -@@ -83,7 +86,7 @@ - #ifdef BT_USE_SSE - - #if (_MSC_FULL_VER >= 170050727)//Visual Studio 2012 can compile SSE4/FMA3 (but SSE4/FMA3 is not enabled by default) -- #define BT_ALLOW_SSE4 -+ //#define BT_ALLOW_SSE4 //disable this cause blender targets sse2 - #endif //(_MSC_FULL_VER >= 160040219) - - //BT_USE_SSE_IN_API is disabled under Windows by default, because -@@ -102,7 +105,7 @@ - #endif //__MINGW32__ - - #ifdef BT_DEBUG -- #ifdef _MSC_VER -+ #if defined(_MSC_VER) && !defined(__clang__) - #include - #define btAssert(x) { if(!(x)){printf("Assert "__FILE__ ":%u ("#x")\n", __LINE__);__debugbreak(); }} - #else//_MSC_VER ++ ++typedef plReal plVector3[3]; ++typedef plReal plQuaternion[4]; ++ ++#ifdef __cplusplus ++extern "C" { ++#endif ++ ++/** Particular physics SDK (C-API) */ ++ PL_DECLARE_HANDLE(plPhysicsSdkHandle); ++ ++/** Dynamics world, belonging to some physics SDK (C-API)*/ ++ PL_DECLARE_HANDLE(plDynamicsWorldHandle); ++ ++/** Rigid Body that can be part of a Dynamics World (C-API)*/ ++ PL_DECLARE_HANDLE(plRigidBodyHandle); ++ ++/** Collision Shape/Geometry, property of a Rigid Body (C-API)*/ ++ PL_DECLARE_HANDLE(plCollisionShapeHandle); ++ ++/** Constraint for Rigid Bodies (C-API)*/ ++ PL_DECLARE_HANDLE(plConstraintHandle); ++ ++/** Triangle Mesh interface (C-API)*/ ++ PL_DECLARE_HANDLE(plMeshInterfaceHandle); ++ ++/** Broadphase Scene/Proxy Handles (C-API)*/ ++ PL_DECLARE_HANDLE(plCollisionBroadphaseHandle); ++ PL_DECLARE_HANDLE(plBroadphaseProxyHandle); ++ PL_DECLARE_HANDLE(plCollisionWorldHandle); ++ ++/** ++ Create and Delete a Physics SDK ++*/ ++ ++ extern plPhysicsSdkHandle plNewBulletSdk(void); //this could be also another sdk, like ODE, PhysX etc. ++ extern void plDeletePhysicsSdk(plPhysicsSdkHandle physicsSdk); ++ ++/** Collision World, not strictly necessary, you can also just create a Dynamics World with Rigid Bodies which internally manages the Collision World with Collision Objects */ ++ ++ typedef void(*btBroadphaseCallback)(void* clientData, void* object1,void* object2); ++ ++ extern plCollisionBroadphaseHandle plCreateSapBroadphase(btBroadphaseCallback beginCallback,btBroadphaseCallback endCallback); ++ ++ extern void plDestroyBroadphase(plCollisionBroadphaseHandle bp); ++ ++ extern plBroadphaseProxyHandle plCreateProxy(plCollisionBroadphaseHandle bp, void* clientData, plReal minX,plReal minY,plReal minZ, plReal maxX,plReal maxY, plReal maxZ); ++ ++ extern void plDestroyProxy(plCollisionBroadphaseHandle bp, plBroadphaseProxyHandle proxyHandle); ++ ++ extern void plSetBoundingBox(plBroadphaseProxyHandle proxyHandle, plReal minX,plReal minY,plReal minZ, plReal maxX,plReal maxY, plReal maxZ); ++ ++/* todo: add pair cache support with queries like add/remove/find pair */ ++ ++ extern plCollisionWorldHandle plCreateCollisionWorld(plPhysicsSdkHandle physicsSdk); ++ ++/* todo: add/remove objects */ ++ ++ ++/* Dynamics World */ ++ ++ extern plDynamicsWorldHandle plCreateDynamicsWorld(plPhysicsSdkHandle physicsSdk); ++ ++ extern void plDeleteDynamicsWorld(plDynamicsWorldHandle world); ++ ++ extern void plStepSimulation(plDynamicsWorldHandle, plReal timeStep); ++ ++ extern void plAddRigidBody(plDynamicsWorldHandle world, plRigidBodyHandle object); ++ ++ extern void plRemoveRigidBody(plDynamicsWorldHandle world, plRigidBodyHandle object); ++ ++ ++/* Rigid Body */ ++ ++ extern plRigidBodyHandle plCreateRigidBody( void* user_data, float mass, plCollisionShapeHandle cshape ); ++ ++ extern void plDeleteRigidBody(plRigidBodyHandle body); ++ ++ ++/* Collision Shape definition */ ++ ++ extern plCollisionShapeHandle plNewSphereShape(plReal radius); ++ extern plCollisionShapeHandle plNewBoxShape(plReal x, plReal y, plReal z); ++ extern plCollisionShapeHandle plNewCapsuleShape(plReal radius, plReal height); ++ extern plCollisionShapeHandle plNewConeShape(plReal radius, plReal height); ++ extern plCollisionShapeHandle plNewCylinderShape(plReal radius, plReal height); ++ extern plCollisionShapeHandle plNewCompoundShape(void); ++ extern void plAddChildShape(plCollisionShapeHandle compoundShape,plCollisionShapeHandle childShape, plVector3 childPos,plQuaternion childOrn); ++ ++ extern void plDeleteShape(plCollisionShapeHandle shape); ++ ++ /* Convex Meshes */ ++ extern plCollisionShapeHandle plNewConvexHullShape(void); ++ extern void plAddVertex(plCollisionShapeHandle convexHull, plReal x,plReal y,plReal z); ++/* Concave static triangle meshes */ ++ extern plMeshInterfaceHandle plNewMeshInterface(void); ++ extern void plAddTriangle(plMeshInterfaceHandle meshHandle, plVector3 v0,plVector3 v1,plVector3 v2); ++ extern plCollisionShapeHandle plNewStaticTriangleMeshShape(plMeshInterfaceHandle); ++ ++ extern void plSetScaling(plCollisionShapeHandle shape, plVector3 scaling); ++ ++/* SOLID has Response Callback/Table/Management */ ++/* PhysX has Triggers, User Callbacks and filtering */ ++/* ODE has the typedef void dNearCallback (void *data, dGeomID o1, dGeomID o2); */ ++ ++/* typedef void plUpdatedPositionCallback(void* userData, plRigidBodyHandle rbHandle, plVector3 pos); */ ++/* typedef void plUpdatedOrientationCallback(void* userData, plRigidBodyHandle rbHandle, plQuaternion orientation); */ ++ ++ /* get world transform */ ++ extern void plGetOpenGLMatrix(plRigidBodyHandle object, plReal* matrix); ++ extern void plGetPosition(plRigidBodyHandle object,plVector3 position); ++ extern void plGetOrientation(plRigidBodyHandle object,plQuaternion orientation); ++ ++ /* set world transform (position/orientation) */ ++ extern void plSetPosition(plRigidBodyHandle object, const plVector3 position); ++ extern void plSetOrientation(plRigidBodyHandle object, const plQuaternion orientation); ++ extern void plSetEuler(plReal yaw,plReal pitch,plReal roll, plQuaternion orient); ++ extern void plSetOpenGLMatrix(plRigidBodyHandle object, plReal* matrix); ++ ++ typedef struct plRayCastResult { ++ plRigidBodyHandle m_body; ++ plCollisionShapeHandle m_shape; ++ plVector3 m_positionWorld; ++ plVector3 m_normalWorld; ++ } plRayCastResult; ++ ++ extern int plRayCast(plDynamicsWorldHandle world, const plVector3 rayStart, const plVector3 rayEnd, plRayCastResult res); ++ ++ /* Sweep API */ ++ ++ /* extern plRigidBodyHandle plObjectCast(plDynamicsWorldHandle world, const plVector3 rayStart, const plVector3 rayEnd, plVector3 hitpoint, plVector3 normal); */ ++ ++ /* Continuous Collision Detection API */ ++ ++ // needed for source/blender/blenkernel/intern/collision.c ++ double plNearestPoints(float p1[3], float p2[3], float p3[3], float q1[3], float q2[3], float q3[3], float *pa, float *pb, float normal[3]); ++ ++ ++ /* Convex Hull */ ++ PL_DECLARE_HANDLE(plConvexHull); ++ plConvexHull plConvexHullCompute(float (*coords)[3], int count); ++ void plConvexHullDelete(plConvexHull hull); ++ int plConvexHullNumVertices(plConvexHull hull); ++ int plConvexHullNumFaces(plConvexHull hull); ++ void plConvexHullGetVertex(plConvexHull hull, int n, float coords[3], int *original_index); ++ int plConvexHullGetFaceSize(plConvexHull hull, int n); ++ void plConvexHullGetFaceVertices(plConvexHull hull, int n, int *vertices); ++ ++#ifdef __cplusplus ++} ++#endif ++ ++ ++#endif //BULLET_C_API_H ++ diff --git a/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionWorld.h b/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionWorld.h -index be9eca6..ec40c96 100644 +index eede2b28ca4..4a3bf0f7e1e 100644 --- a/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionWorld.h +++ b/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionWorld.h @@ -15,7 +15,7 @@ subject to the following restrictions: @@ -42,145 +229,8 @@ index be9eca6..ec40c96 100644 * * @section intro_sec Introduction * Bullet is a Collision Detection and Rigid Body Dynamics Library. The Library is Open Source and free for commercial use, under the ZLib license ( http://opensource.org/licenses/zlib-license.php ). -diff --git a/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionWorldImporter.cpp b/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionWorldImporter.cpp -index 36dd043..57eb817 100644 ---- a/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionWorldImporter.cpp -+++ b/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionWorldImporter.cpp -@@ -579,14 +579,10 @@ btCollisionShape* btCollisionWorldImporter::convertCollisionShape( btCollisionS - btCompoundShapeData* compoundData = (btCompoundShapeData*)shapeData; - btCompoundShape* compoundShape = createCompoundShape(); - -- btCompoundShapeChildData* childShapeDataArray = &compoundData->m_childShapePtr[0]; -- - - btAlignedObjectArray childShapes; - for (int i=0;im_numChildShapes;i++) - { -- btCompoundShapeChildData* ptr = &compoundData->m_childShapePtr[i]; -- - btCollisionShapeData* cd = compoundData->m_childShapePtr[i].m_childShape; - - btCollisionShape* childShape = convertCollisionShape(cd); -diff --git a/extern/bullet/src/BulletDynamics/Character/btKinematicCharacterController.cpp b/extern/bullet/src/BulletDynamics/Character/btKinematicCharacterController.cpp -index 57fc119..31faf1d 100644 ---- a/extern/bullet/src/BulletDynamics/Character/btKinematicCharacterController.cpp -+++ b/extern/bullet/src/BulletDynamics/Character/btKinematicCharacterController.cpp -@@ -29,14 +29,11 @@ subject to the following restrictions: - static btVector3 - getNormalizedVector(const btVector3& v) - { -- btScalar l = v.length(); -- btVector3 n = v; -- if (l < SIMD_EPSILON) { -- n.setValue(0,0,0); -- } else { -- n /= l; -- } -+ btVector3 n(0, 0, 0); - -+ if (v.length() > SIMD_EPSILON) { -+ n = v.normalized(); -+ } - return n; - } - -diff --git a/extern/bullet/src/BulletDynamics/ConstraintSolver/btSolverBody.h b/extern/bullet/src/BulletDynamics/ConstraintSolver/btSolverBody.h -index 27ccefe..8e4456e 100644 ---- a/extern/bullet/src/BulletDynamics/ConstraintSolver/btSolverBody.h -+++ b/extern/bullet/src/BulletDynamics/ConstraintSolver/btSolverBody.h -@@ -37,8 +37,13 @@ struct btSimdScalar - { - - } -- -+/* workaround for clang 3.4 ( == apple clang 5.1 ) issue, friction would fail with forced inlining */ -+#if (defined(__clang__) && defined(__apple_build_version__) && (__clang_major__ == 5) && (__clang_minor__ == 1)) \ -+|| (defined(__clang__) && !defined(__apple_build_version__) && (__clang_major__ == 3) && (__clang_minor__ == 4)) -+ inline __attribute__ ((noinline)) btSimdScalar(float fl) -+#else - SIMD_FORCE_INLINE btSimdScalar(float fl) -+#endif - :m_vec128 (_mm_set1_ps(fl)) - { - } -diff --git a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBody.cpp b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBody.cpp -index 5d62da7..fcd312e 100644 ---- a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBody.cpp -+++ b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBody.cpp -@@ -28,7 +28,6 @@ - #include "btMultiBodyJointFeedback.h" - #include "LinearMath/btTransformUtil.h" - #include "LinearMath/btSerializer.h" --#include "Bullet3Common/b3Logging.h" - // #define INCLUDE_GYRO_TERM - - ///todo: determine if we need these options. If so, make a proper API, otherwise delete those globals -@@ -1732,7 +1731,6 @@ void btMultiBody::goToSleep() - - void btMultiBody::checkMotionAndSleepIfRequired(btScalar timestep) - { -- int num_links = getNumLinks(); - extern bool gDisableDeactivation; - if (!m_canSleep || gDisableDeactivation) - { -diff --git a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp -index 8a034b3..4f66b20 100644 ---- a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp -+++ b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp -@@ -809,7 +809,6 @@ static void applyJointFeedback(btMultiBodyJacobianData& data, const btMultiBodyS - } - #endif - --#include "Bullet3Common/b3Logging.h" - void btMultiBodyConstraintSolver::writeBackSolverBodyToMultiBody(btMultiBodySolverConstraint& c, btScalar deltaTime) - { - #if 1 -diff --git a/extern/bullet/src/BulletSoftBody/btSparseSDF.h b/extern/bullet/src/BulletSoftBody/btSparseSDF.h -index bcf0c79..8992ddb 100644 ---- a/extern/bullet/src/BulletSoftBody/btSparseSDF.h -+++ b/extern/bullet/src/BulletSoftBody/btSparseSDF.h -@@ -185,7 +185,6 @@ struct btSparseSdf - { - ++nprobes; - ++ncells; -- int sz = sizeof(Cell); - if (ncells>m_clampCells) - { - static int numResets=0; -diff --git a/extern/bullet/src/LinearMath/btConvexHullComputer.cpp b/extern/bullet/src/LinearMath/btConvexHullComputer.cpp -index d58ac95..3fd77df 100644 ---- a/extern/bullet/src/LinearMath/btConvexHullComputer.cpp -+++ b/extern/bullet/src/LinearMath/btConvexHullComputer.cpp -@@ -2665,6 +2665,7 @@ btScalar btConvexHullComputer::compute(const void* coords, bool doubleCoords, in - } - - vertices.resize(0); -+ original_vertex_index.resize(0); - edges.resize(0); - faces.resize(0); - -@@ -2675,6 +2676,7 @@ btScalar btConvexHullComputer::compute(const void* coords, bool doubleCoords, in - { - btConvexHullInternal::Vertex* v = oldVertices[copied]; - vertices.push_back(hull.getCoordinates(v)); -+ original_vertex_index.push_back(v->point.index); - btConvexHullInternal::Edge* firstEdge = v->edges; - if (firstEdge) - { -diff --git a/extern/bullet/src/LinearMath/btConvexHullComputer.h b/extern/bullet/src/LinearMath/btConvexHullComputer.h -index 7240ac4..6871ce8 100644 ---- a/extern/bullet/src/LinearMath/btConvexHullComputer.h -+++ b/extern/bullet/src/LinearMath/btConvexHullComputer.h -@@ -67,6 +67,7 @@ class btConvexHullComputer - - // Vertices of the output hull - btAlignedObjectArray vertices; -+ btAlignedObjectArray original_vertex_index; - - // Edges of the output hull - btAlignedObjectArray edges; diff --git a/extern/bullet/src/BulletCollision/CollisionShapes/btConvexHullShape.cpp b/extern/bullet/src/BulletCollision/CollisionShapes/btConvexHullShape.cpp -index 0623e35..02ea503 100644 +index a7a9598406a..eec2b8d769e 100644 --- a/extern/bullet/src/BulletCollision/CollisionShapes/btConvexHullShape.cpp +++ b/extern/bullet/src/BulletCollision/CollisionShapes/btConvexHullShape.cpp @@ -13,9 +13,9 @@ subject to the following restrictions: @@ -197,7 +247,7 @@ index 0623e35..02ea503 100644 #include "btConvexHullShape.h" #include "BulletCollision/CollisionShapes/btCollisionMargin.h" diff --git a/extern/bullet/src/BulletCollision/CollisionShapes/btConvexShape.cpp b/extern/bullet/src/BulletCollision/CollisionShapes/btConvexShape.cpp -index b56d729..88018b4 100644 +index 8d7fb054d6b..b31fbdcf237 100644 --- a/extern/bullet/src/BulletCollision/CollisionShapes/btConvexShape.cpp +++ b/extern/bullet/src/BulletCollision/CollisionShapes/btConvexShape.cpp @@ -13,9 +13,9 @@ subject to the following restrictions: @@ -214,7 +264,7 @@ index b56d729..88018b4 100644 #include "btConvexShape.h" #include "btTriangleShape.h" diff --git a/extern/bullet/src/BulletCollision/CollisionShapes/btMultiSphereShape.cpp b/extern/bullet/src/BulletCollision/CollisionShapes/btMultiSphereShape.cpp -index a7362ea..6abfdff 100644 +index 4195fa31388..d5bf6d60fe3 100644 --- a/extern/bullet/src/BulletCollision/CollisionShapes/btMultiSphereShape.cpp +++ b/extern/bullet/src/BulletCollision/CollisionShapes/btMultiSphereShape.cpp @@ -13,9 +13,9 @@ subject to the following restrictions: @@ -231,7 +281,7 @@ index a7362ea..6abfdff 100644 #include "btMultiSphereShape.h" #include "BulletCollision/CollisionShapes/btCollisionMargin.h" diff --git a/extern/bullet/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.cpp b/extern/bullet/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.cpp -index 4854f37..9095c59 100644 +index 4854f370f73..9095c592d87 100644 --- a/extern/bullet/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.cpp +++ b/extern/bullet/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.cpp @@ -12,9 +12,9 @@ subject to the following restrictions: @@ -247,28 +297,505 @@ index 4854f37..9095c59 100644 #include "BulletCollision/CollisionShapes/btPolyhedralConvexShape.h" #include "btConvexPolyhedron.h" -diff --git a/extern/bullet/src/LinearMath/btVector3.cpp b/extern/bullet/src/LinearMath/btVector3.cpp -index e05bdcc..dbcf2b6 100644 ---- a/extern/bullet/src/LinearMath/btVector3.cpp -+++ b/extern/bullet/src/LinearMath/btVector3.cpp -@@ -15,9 +15,9 @@ - This source version has been altered. - */ - --#if defined (_WIN32) || defined (__i386__) --#define BT_USE_SSE_IN_API --#endif -+//#if defined (_WIN32) || defined (__i386__) -+//#define BT_USE_SSE_IN_API -+//#endif - +diff --git a/extern/bullet/src/BulletDynamics/ConstraintSolver/btSolverBody.h b/extern/bullet/src/BulletDynamics/ConstraintSolver/btSolverBody.h +index 27ccefe4169..8e4456e617a 100644 +--- a/extern/bullet/src/BulletDynamics/ConstraintSolver/btSolverBody.h ++++ b/extern/bullet/src/BulletDynamics/ConstraintSolver/btSolverBody.h +@@ -37,8 +37,13 @@ struct btSimdScalar + { - #include "btVector3.h" + } +- ++/* workaround for clang 3.4 ( == apple clang 5.1 ) issue, friction would fail with forced inlining */ ++#if (defined(__clang__) && defined(__apple_build_version__) && (__clang_major__ == 5) && (__clang_minor__ == 1)) \ ++|| (defined(__clang__) && !defined(__apple_build_version__) && (__clang_major__ == 3) && (__clang_minor__ == 4)) ++ inline __attribute__ ((noinline)) btSimdScalar(float fl) ++#else + SIMD_FORCE_INLINE btSimdScalar(float fl) ++#endif + :m_vec128 (_mm_set1_ps(fl)) + { + } +diff --git a/extern/bullet/src/BulletDynamics/Dynamics/Bullet-C-API.cpp b/extern/bullet/src/BulletDynamics/Dynamics/Bullet-C-API.cpp +new file mode 100644 +index 00000000000..e1f69afe101 +--- /dev/null ++++ b/extern/bullet/src/BulletDynamics/Dynamics/Bullet-C-API.cpp +@@ -0,0 +1,469 @@ ++/* ++Bullet Continuous Collision Detection and Physics Library ++Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ ++ ++This software is provided 'as-is', without any express or implied warranty. ++In no event will the authors be held liable for any damages arising from the use of this software. ++Permission is granted to anyone to use this software for any purpose, ++including commercial applications, and to alter it and redistribute it freely, ++subject to the following restrictions: ++ ++1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. ++2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. ++3. This notice may not be removed or altered from any source distribution. ++*/ ++ ++/* ++ Draft high-level generic physics C-API. For low-level access, use the physics SDK native API's. ++ Work in progress, functionality will be added on demand. ++ ++ If possible, use the richer Bullet C++ API, by including ++*/ ++ ++#include "Bullet-C-Api.h" ++#include "btBulletDynamicsCommon.h" ++#include "LinearMath/btAlignedAllocator.h" ++#include "LinearMath/btConvexHullComputer.h" ++ ++ ++#include "LinearMath/btVector3.h" ++#include "LinearMath/btScalar.h" ++#include "LinearMath/btMatrix3x3.h" ++#include "LinearMath/btTransform.h" ++#include "BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h" ++#include "BulletCollision/CollisionShapes/btTriangleShape.h" ++#include "BulletCollision/Gimpact/btTriangleShapeEx.h" ++ ++#include "BulletCollision/NarrowPhaseCollision/btGjkPairDetector.h" ++#include "BulletCollision/NarrowPhaseCollision/btPointCollector.h" ++#include "BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h" ++#include "BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.h" ++#include "BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.h" ++#include "BulletCollision/NarrowPhaseCollision/btGjkEpa2.h" ++#include "BulletCollision/CollisionShapes/btMinkowskiSumShape.h" ++#include "BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h" ++#include "BulletCollision/NarrowPhaseCollision/btSimplexSolverInterface.h" ++#include "BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.h" ++ ++ ++/* ++ Create and Delete a Physics SDK ++*/ ++ ++struct btPhysicsSdk ++{ ++ ++// btDispatcher* m_dispatcher; ++// btOverlappingPairCache* m_pairCache; ++// btConstraintSolver* m_constraintSolver ++ ++ btVector3 m_worldAabbMin; ++ btVector3 m_worldAabbMax; ++ ++ ++ //todo: version, hardware/optimization settings etc? ++ btPhysicsSdk() ++ :m_worldAabbMin(-1000,-1000,-1000), ++ m_worldAabbMax(1000,1000,1000) ++ { ++ ++ } ++ ++ ++}; ++ ++plPhysicsSdkHandle plNewBulletSdk() ++{ ++ void* mem = btAlignedAlloc(sizeof(btPhysicsSdk),16); ++ return (plPhysicsSdkHandle)new (mem)btPhysicsSdk; ++} ++ ++void plDeletePhysicsSdk(plPhysicsSdkHandle physicsSdk) ++{ ++ btPhysicsSdk* phys = reinterpret_cast(physicsSdk); ++ btAlignedFree(phys); ++} ++ ++ ++/* Dynamics World */ ++plDynamicsWorldHandle plCreateDynamicsWorld(plPhysicsSdkHandle physicsSdkHandle) ++{ ++ btPhysicsSdk* physicsSdk = reinterpret_cast(physicsSdkHandle); ++ void* mem = btAlignedAlloc(sizeof(btDefaultCollisionConfiguration),16); ++ btDefaultCollisionConfiguration* collisionConfiguration = new (mem)btDefaultCollisionConfiguration(); ++ mem = btAlignedAlloc(sizeof(btCollisionDispatcher),16); ++ btDispatcher* dispatcher = new (mem)btCollisionDispatcher(collisionConfiguration); ++ mem = btAlignedAlloc(sizeof(btAxisSweep3),16); ++ btBroadphaseInterface* pairCache = new (mem)btAxisSweep3(physicsSdk->m_worldAabbMin,physicsSdk->m_worldAabbMax); ++ mem = btAlignedAlloc(sizeof(btSequentialImpulseConstraintSolver),16); ++ btConstraintSolver* constraintSolver = new(mem) btSequentialImpulseConstraintSolver(); ++ ++ mem = btAlignedAlloc(sizeof(btDiscreteDynamicsWorld),16); ++ return (plDynamicsWorldHandle) new (mem)btDiscreteDynamicsWorld(dispatcher,pairCache,constraintSolver,collisionConfiguration); ++} ++void plDeleteDynamicsWorld(plDynamicsWorldHandle world) ++{ ++ //todo: also clean up the other allocations, axisSweep, pairCache,dispatcher,constraintSolver,collisionConfiguration ++ btDynamicsWorld* dynamicsWorld = reinterpret_cast< btDynamicsWorld* >(world); ++ btAlignedFree(dynamicsWorld); ++} ++ ++void plStepSimulation(plDynamicsWorldHandle world, plReal timeStep) ++{ ++ btDynamicsWorld* dynamicsWorld = reinterpret_cast< btDynamicsWorld* >(world); ++ btAssert(dynamicsWorld); ++ dynamicsWorld->stepSimulation(timeStep); ++} ++ ++void plAddRigidBody(plDynamicsWorldHandle world, plRigidBodyHandle object) ++{ ++ btDynamicsWorld* dynamicsWorld = reinterpret_cast< btDynamicsWorld* >(world); ++ btAssert(dynamicsWorld); ++ btRigidBody* body = reinterpret_cast< btRigidBody* >(object); ++ btAssert(body); ++ ++ dynamicsWorld->addRigidBody(body); ++} ++ ++void plRemoveRigidBody(plDynamicsWorldHandle world, plRigidBodyHandle object) ++{ ++ btDynamicsWorld* dynamicsWorld = reinterpret_cast< btDynamicsWorld* >(world); ++ btAssert(dynamicsWorld); ++ btRigidBody* body = reinterpret_cast< btRigidBody* >(object); ++ btAssert(body); ++ ++ dynamicsWorld->removeRigidBody(body); ++} ++ ++/* Rigid Body */ ++ ++plRigidBodyHandle plCreateRigidBody( void* user_data, float mass, plCollisionShapeHandle cshape ) ++{ ++ btTransform trans; ++ trans.setIdentity(); ++ btVector3 localInertia(0,0,0); ++ btCollisionShape* shape = reinterpret_cast( cshape); ++ btAssert(shape); ++ if (mass) ++ { ++ shape->calculateLocalInertia(mass,localInertia); ++ } ++ void* mem = btAlignedAlloc(sizeof(btRigidBody),16); ++ btRigidBody::btRigidBodyConstructionInfo rbci(mass, 0,shape,localInertia); ++ btRigidBody* body = new (mem)btRigidBody(rbci); ++ body->setWorldTransform(trans); ++ body->setUserPointer(user_data); ++ return (plRigidBodyHandle) body; ++} ++ ++void plDeleteRigidBody(plRigidBodyHandle cbody) ++{ ++ btRigidBody* body = reinterpret_cast< btRigidBody* >(cbody); ++ btAssert(body); ++ btAlignedFree( body); ++} ++ ++ ++/* Collision Shape definition */ ++ ++plCollisionShapeHandle plNewSphereShape(plReal radius) ++{ ++ void* mem = btAlignedAlloc(sizeof(btSphereShape),16); ++ return (plCollisionShapeHandle) new (mem)btSphereShape(radius); ++ ++} ++ ++plCollisionShapeHandle plNewBoxShape(plReal x, plReal y, plReal z) ++{ ++ void* mem = btAlignedAlloc(sizeof(btBoxShape),16); ++ return (plCollisionShapeHandle) new (mem)btBoxShape(btVector3(x,y,z)); ++} ++ ++plCollisionShapeHandle plNewCapsuleShape(plReal radius, plReal height) ++{ ++ //capsule is convex hull of 2 spheres, so use btMultiSphereShape ++ ++ const int numSpheres = 2; ++ btVector3 positions[numSpheres] = {btVector3(0,height,0),btVector3(0,-height,0)}; ++ btScalar radi[numSpheres] = {radius,radius}; ++ void* mem = btAlignedAlloc(sizeof(btMultiSphereShape),16); ++ return (plCollisionShapeHandle) new (mem)btMultiSphereShape(positions,radi,numSpheres); ++} ++plCollisionShapeHandle plNewConeShape(plReal radius, plReal height) ++{ ++ void* mem = btAlignedAlloc(sizeof(btConeShape),16); ++ return (plCollisionShapeHandle) new (mem)btConeShape(radius,height); ++} ++ ++plCollisionShapeHandle plNewCylinderShape(plReal radius, plReal height) ++{ ++ void* mem = btAlignedAlloc(sizeof(btCylinderShape),16); ++ return (plCollisionShapeHandle) new (mem)btCylinderShape(btVector3(radius,height,radius)); ++} ++ ++/* Convex Meshes */ ++plCollisionShapeHandle plNewConvexHullShape() ++{ ++ void* mem = btAlignedAlloc(sizeof(btConvexHullShape),16); ++ return (plCollisionShapeHandle) new (mem)btConvexHullShape(); ++} ++ ++ ++/* Concave static triangle meshes */ ++plMeshInterfaceHandle plNewMeshInterface() ++{ ++ return 0; ++} ++ ++plCollisionShapeHandle plNewCompoundShape() ++{ ++ void* mem = btAlignedAlloc(sizeof(btCompoundShape),16); ++ return (plCollisionShapeHandle) new (mem)btCompoundShape(); ++} ++ ++void plAddChildShape(plCollisionShapeHandle compoundShapeHandle,plCollisionShapeHandle childShapeHandle, plVector3 childPos,plQuaternion childOrn) ++{ ++ btCollisionShape* colShape = reinterpret_cast(compoundShapeHandle); ++ btAssert(colShape->getShapeType() == COMPOUND_SHAPE_PROXYTYPE); ++ btCompoundShape* compoundShape = reinterpret_cast(colShape); ++ btCollisionShape* childShape = reinterpret_cast(childShapeHandle); ++ btTransform localTrans; ++ localTrans.setIdentity(); ++ localTrans.setOrigin(btVector3(childPos[0],childPos[1],childPos[2])); ++ localTrans.setRotation(btQuaternion(childOrn[0],childOrn[1],childOrn[2],childOrn[3])); ++ compoundShape->addChildShape(localTrans,childShape); ++} ++ ++void plSetEuler(plReal yaw,plReal pitch,plReal roll, plQuaternion orient) ++{ ++ btQuaternion orn; ++ orn.setEuler(yaw,pitch,roll); ++ orient[0] = orn.getX(); ++ orient[1] = orn.getY(); ++ orient[2] = orn.getZ(); ++ orient[3] = orn.getW(); ++ ++} ++ ++ ++// extern void plAddTriangle(plMeshInterfaceHandle meshHandle, plVector3 v0,plVector3 v1,plVector3 v2); ++// extern plCollisionShapeHandle plNewStaticTriangleMeshShape(plMeshInterfaceHandle); ++ ++ ++void plAddVertex(plCollisionShapeHandle cshape, plReal x,plReal y,plReal z) ++{ ++ btCollisionShape* colShape = reinterpret_cast( cshape); ++ (void)colShape; ++ btAssert(colShape->getShapeType()==CONVEX_HULL_SHAPE_PROXYTYPE); ++ btConvexHullShape* convexHullShape = reinterpret_cast( cshape); ++ convexHullShape->addPoint(btVector3(x,y,z)); ++ ++} ++ ++void plDeleteShape(plCollisionShapeHandle cshape) ++{ ++ btCollisionShape* shape = reinterpret_cast( cshape); ++ btAssert(shape); ++ btAlignedFree(shape); ++} ++void plSetScaling(plCollisionShapeHandle cshape, plVector3 cscaling) ++{ ++ btCollisionShape* shape = reinterpret_cast( cshape); ++ btAssert(shape); ++ btVector3 scaling(cscaling[0],cscaling[1],cscaling[2]); ++ shape->setLocalScaling(scaling); ++} ++ ++ ++ ++void plSetPosition(plRigidBodyHandle object, const plVector3 position) ++{ ++ btRigidBody* body = reinterpret_cast< btRigidBody* >(object); ++ btAssert(body); ++ btVector3 pos(position[0],position[1],position[2]); ++ btTransform worldTrans = body->getWorldTransform(); ++ worldTrans.setOrigin(pos); ++ body->setWorldTransform(worldTrans); ++} ++ ++void plSetOrientation(plRigidBodyHandle object, const plQuaternion orientation) ++{ ++ btRigidBody* body = reinterpret_cast< btRigidBody* >(object); ++ btAssert(body); ++ btQuaternion orn(orientation[0],orientation[1],orientation[2],orientation[3]); ++ btTransform worldTrans = body->getWorldTransform(); ++ worldTrans.setRotation(orn); ++ body->setWorldTransform(worldTrans); ++} ++ ++void plSetOpenGLMatrix(plRigidBodyHandle object, plReal* matrix) ++{ ++ btRigidBody* body = reinterpret_cast< btRigidBody* >(object); ++ btAssert(body); ++ btTransform& worldTrans = body->getWorldTransform(); ++ worldTrans.setFromOpenGLMatrix(matrix); ++} ++ ++void plGetOpenGLMatrix(plRigidBodyHandle object, plReal* matrix) ++{ ++ btRigidBody* body = reinterpret_cast< btRigidBody* >(object); ++ btAssert(body); ++ body->getWorldTransform().getOpenGLMatrix(matrix); ++ ++} ++ ++void plGetPosition(plRigidBodyHandle object,plVector3 position) ++{ ++ btRigidBody* body = reinterpret_cast< btRigidBody* >(object); ++ btAssert(body); ++ const btVector3& pos = body->getWorldTransform().getOrigin(); ++ position[0] = pos.getX(); ++ position[1] = pos.getY(); ++ position[2] = pos.getZ(); ++} ++ ++void plGetOrientation(plRigidBodyHandle object,plQuaternion orientation) ++{ ++ btRigidBody* body = reinterpret_cast< btRigidBody* >(object); ++ btAssert(body); ++ const btQuaternion& orn = body->getWorldTransform().getRotation(); ++ orientation[0] = orn.getX(); ++ orientation[1] = orn.getY(); ++ orientation[2] = orn.getZ(); ++ orientation[3] = orn.getW(); ++} ++ ++ ++ ++//plRigidBodyHandle plRayCast(plDynamicsWorldHandle world, const plVector3 rayStart, const plVector3 rayEnd, plVector3 hitpoint, plVector3 normal); ++ ++// extern plRigidBodyHandle plObjectCast(plDynamicsWorldHandle world, const plVector3 rayStart, const plVector3 rayEnd, plVector3 hitpoint, plVector3 normal); ++ ++double plNearestPoints(float p1[3], float p2[3], float p3[3], float q1[3], float q2[3], float q3[3], float *pa, float *pb, float normal[3]) ++{ ++ btVector3 vp(p1[0], p1[1], p1[2]); ++ btTriangleShapeEx trishapeA(vp, ++ btVector3(p2[0], p2[1], p2[2]), ++ btVector3(p3[0], p3[1], p3[2])); ++ trishapeA.setMargin(0.000001f); ++ btVector3 vq(q1[0], q1[1], q1[2]); ++ btTriangleShapeEx trishapeB(vq, ++ btVector3(q2[0], q2[1], q2[2]), ++ btVector3(q3[0], q3[1], q3[2])); ++ trishapeB.setMargin(0.000001f); ++ ++ // btVoronoiSimplexSolver sGjkSimplexSolver; ++ // btGjkEpaPenetrationDepthSolver penSolverPtr; ++ ++ /*static*/ btSimplexSolverInterface sGjkSimplexSolver; ++ sGjkSimplexSolver.reset(); ++ ++ /*static*/ btGjkEpaPenetrationDepthSolver Solver0; ++ /*static*/ btMinkowskiPenetrationDepthSolver Solver1; ++ ++ btConvexPenetrationDepthSolver* Solver = NULL; ++ ++ Solver = &Solver1; ++ ++ btGjkPairDetector convexConvex(&trishapeA ,&trishapeB,&sGjkSimplexSolver,Solver); ++ ++ convexConvex.m_catchDegeneracies = 1; ++ ++ // btGjkPairDetector convexConvex(&trishapeA ,&trishapeB,&sGjkSimplexSolver,0); ++ ++ btPointCollector gjkOutput; ++ btGjkPairDetector::ClosestPointInput input; ++ ++ ++ btTransform tr; ++ tr.setIdentity(); ++ ++ input.m_transformA = tr; ++ input.m_transformB = tr; ++ ++ convexConvex.getClosestPoints(input, gjkOutput, 0); ++ ++ ++ if (gjkOutput.m_hasResult) ++ { ++ ++ pb[0] = pa[0] = gjkOutput.m_pointInWorld[0]; ++ pb[1] = pa[1] = gjkOutput.m_pointInWorld[1]; ++ pb[2] = pa[2] = gjkOutput.m_pointInWorld[2]; ++ ++ pb[0]+= gjkOutput.m_normalOnBInWorld[0] * gjkOutput.m_distance; ++ pb[1]+= gjkOutput.m_normalOnBInWorld[1] * gjkOutput.m_distance; ++ pb[2]+= gjkOutput.m_normalOnBInWorld[2] * gjkOutput.m_distance; ++ ++ normal[0] = gjkOutput.m_normalOnBInWorld[0]; ++ normal[1] = gjkOutput.m_normalOnBInWorld[1]; ++ normal[2] = gjkOutput.m_normalOnBInWorld[2]; ++ ++ return gjkOutput.m_distance; ++ } ++ return -1.0f; ++} ++ ++// Convex hull ++plConvexHull plConvexHullCompute(float (*coords)[3], int count) ++{ ++ btConvexHullComputer *computer = new btConvexHullComputer; ++ computer->compute(reinterpret_cast< float* >(coords), ++ sizeof(*coords), count, 0, 0); ++ return reinterpret_cast(computer); ++} ++ ++void plConvexHullDelete(plConvexHull hull) ++{ ++ btConvexHullComputer *computer(reinterpret_cast< btConvexHullComputer* >(hull)); ++ delete computer; ++} ++ ++int plConvexHullNumVertices(plConvexHull hull) ++{ ++ btConvexHullComputer *computer(reinterpret_cast< btConvexHullComputer* >(hull)); ++ return computer->vertices.size(); ++} ++ ++int plConvexHullNumFaces(plConvexHull hull) ++{ ++ btConvexHullComputer *computer(reinterpret_cast< btConvexHullComputer* >(hull)); ++ return computer->faces.size(); ++} ++ ++void plConvexHullGetVertex(plConvexHull hull, int n, float coords[3], ++ int *original_index) ++{ ++ btConvexHullComputer *computer(reinterpret_cast< btConvexHullComputer* >(hull)); ++ const btVector3 &v(computer->vertices[n]); ++ coords[0] = v[0]; ++ coords[1] = v[1]; ++ coords[2] = v[2]; ++ (*original_index) = computer->original_vertex_index[n]; ++} ++ ++int plConvexHullGetFaceSize(plConvexHull hull, int n) ++{ ++ btConvexHullComputer *computer(reinterpret_cast< btConvexHullComputer* >(hull)); ++ const btConvexHullComputer::Edge *e_orig, *e; ++ int count; ++ ++ for (e_orig = &computer->edges[computer->faces[n]], e = e_orig, count = 0; ++ count == 0 || e != e_orig; ++ e = e->getNextEdgeOfFace(), count++); ++ return count; ++} ++ ++void plConvexHullGetFaceVertices(plConvexHull hull, int n, int *vertices) ++{ ++ btConvexHullComputer *computer(reinterpret_cast< btConvexHullComputer* >(hull)); ++ const btConvexHullComputer::Edge *e_orig, *e; ++ int count; ++ ++ for (e_orig = &computer->edges[computer->faces[n]], e = e_orig, count = 0; ++ count == 0 || e != e_orig; ++ e = e->getNextEdgeOfFace(), count++) ++ { ++ vertices[count] = e->getTargetVertex(); ++ } ++} diff --git a/extern/bullet/src/BulletDynamics/Dynamics/btRigidBody.cpp b/extern/bullet/src/BulletDynamics/Dynamics/btRigidBody.cpp -index e0e8bc7..a788268 100644 +index ca0714fcfa8..a9f27496212 100644 --- a/extern/bullet/src/BulletDynamics/Dynamics/btRigidBody.cpp +++ b/extern/bullet/src/BulletDynamics/Dynamics/btRigidBody.cpp -@@ -425,50 +425,38 @@ void btRigidBody::setCenterOfMassTransform(const btTransform& xform) +@@ -427,50 +427,38 @@ void btRigidBody::setCenterOfMassTransform(const btTransform& xform) } @@ -341,10 +868,10 @@ index e0e8bc7..a788268 100644 int btRigidBody::calculateSerializeBufferSize() const diff --git a/extern/bullet/src/BulletDynamics/Dynamics/btRigidBody.h b/extern/bullet/src/BulletDynamics/Dynamics/btRigidBody.h -index 1d177db..c2f8c5d 100644 +index 372245031b1..dbbf9958618 100644 --- a/extern/bullet/src/BulletDynamics/Dynamics/btRigidBody.h +++ b/extern/bullet/src/BulletDynamics/Dynamics/btRigidBody.h -@@ -509,6 +509,8 @@ public: +@@ -512,6 +512,8 @@ public: return (getBroadphaseProxy() != 0); } @@ -353,3 +880,78 @@ index 1d177db..c2f8c5d 100644 void addConstraintRef(btTypedConstraint* c); void removeConstraintRef(btTypedConstraint* c); +diff --git a/extern/bullet/src/LinearMath/btConvexHullComputer.cpp b/extern/bullet/src/LinearMath/btConvexHullComputer.cpp +index 2ea22cbe3ba..efe9a171bec 100644 +--- a/extern/bullet/src/LinearMath/btConvexHullComputer.cpp ++++ b/extern/bullet/src/LinearMath/btConvexHullComputer.cpp +@@ -2678,6 +2678,7 @@ btScalar btConvexHullComputer::compute(const void* coords, bool doubleCoords, in + } + + vertices.resize(0); ++ original_vertex_index.resize(0); + edges.resize(0); + faces.resize(0); + +@@ -2688,6 +2689,7 @@ btScalar btConvexHullComputer::compute(const void* coords, bool doubleCoords, in + { + btConvexHullInternal::Vertex* v = oldVertices[copied]; + vertices.push_back(hull.getCoordinates(v)); ++ original_vertex_index.push_back(v->point.index); + btConvexHullInternal::Edge* firstEdge = v->edges; + if (firstEdge) + { +diff --git a/extern/bullet/src/LinearMath/btConvexHullComputer.h b/extern/bullet/src/LinearMath/btConvexHullComputer.h +index 7240ac4fb52..6871ce80e00 100644 +--- a/extern/bullet/src/LinearMath/btConvexHullComputer.h ++++ b/extern/bullet/src/LinearMath/btConvexHullComputer.h +@@ -67,6 +67,7 @@ class btConvexHullComputer + + // Vertices of the output hull + btAlignedObjectArray vertices; ++ btAlignedObjectArray original_vertex_index; + + // Edges of the output hull + btAlignedObjectArray edges; +diff --git a/extern/bullet/src/LinearMath/btScalar.h b/extern/bullet/src/LinearMath/btScalar.h +index bffb2ce274e..47b00385057 100644 +--- a/extern/bullet/src/LinearMath/btScalar.h ++++ b/extern/bullet/src/LinearMath/btScalar.h +@@ -14,6 +14,9 @@ subject to the following restrictions: + + #ifndef BT_SCALAR_H + #define BT_SCALAR_H ++#if defined(_MSC_VER) && defined(__clang__) /* clang supplies it's own overloads already */ ++#define BT_NO_SIMD_OPERATOR_OVERLOADS ++#endif + + #ifdef BT_MANAGED_CODE + //Aligned data types not supported in managed code +@@ -101,7 +104,7 @@ inline int btGetVersion() + #ifdef BT_USE_SSE + + #if (_MSC_FULL_VER >= 170050727)//Visual Studio 2012 can compile SSE4/FMA3 (but SSE4/FMA3 is not enabled by default) +- #define BT_ALLOW_SSE4 ++ //#define BT_ALLOW_SSE4 //disable this cause blender targets sse2 + #endif //(_MSC_FULL_VER >= 160040219) + + //BT_USE_SSE_IN_API is disabled under Windows by default, because +diff --git a/extern/bullet/src/LinearMath/btVector3.cpp b/extern/bullet/src/LinearMath/btVector3.cpp +index e05bdccd67e..dbcf2b6ab57 100644 +--- a/extern/bullet/src/LinearMath/btVector3.cpp ++++ b/extern/bullet/src/LinearMath/btVector3.cpp +@@ -15,9 +15,9 @@ + This source version has been altered. + */ + +-#if defined (_WIN32) || defined (__i386__) +-#define BT_USE_SSE_IN_API +-#endif ++//#if defined (_WIN32) || defined (__i386__) ++//#define BT_USE_SSE_IN_API ++//#endif + + + #include "btVector3.h" +-- +2.18.0 + diff --git a/extern/bullet/patches/character-ghost.patch b/extern/bullet/patches/character-ghost.patch new file mode 100644 index 000000000000..4aa5532168c6 --- /dev/null +++ b/extern/bullet/patches/character-ghost.patch @@ -0,0 +1,131 @@ +From 3f6c099a3a9f78c7862448f42df61df9b1cd41cb Mon Sep 17 00:00:00 2001 +From: tristan +Date: Fri, 12 Oct 2018 19:26:23 +0200 +Subject: [PATCH] temp + +--- + .../btKinematicCharacterController.cpp | 32 +++++++++++-------- + .../btKinematicCharacterController.h | 8 ++--- + 2 files changed, 23 insertions(+), 17 deletions(-) + +diff --git a/extern/bullet/src/BulletDynamics/Character/btKinematicCharacterController.cpp b/extern/bullet/src/BulletDynamics/Character/btKinematicCharacterController.cpp +index cb1aa71a14e..4a6ce16a4e2 100644 +--- a/extern/bullet/src/BulletDynamics/Character/btKinematicCharacterController.cpp ++++ b/extern/bullet/src/BulletDynamics/Character/btKinematicCharacterController.cpp +@@ -132,7 +132,7 @@ btVector3 btKinematicCharacterController::perpindicularComponent (const btVector + return direction - parallelComponent(direction, normal); + } + +-btKinematicCharacterController::btKinematicCharacterController (btPairCachingGhostObject* ghostObject,btConvexShape* convexShape,btScalar stepHeight, const btVector3& up) ++btKinematicCharacterController::btKinematicCharacterController (btGhostObject* ghostObject,btConvexShape* convexShape,btScalar stepHeight, const btVector3& up) + { + m_ghostObject = ghostObject; + m_up.setValue(0.0f, 0.0f, 1.0f); +@@ -170,7 +170,7 @@ btKinematicCharacterController::~btKinematicCharacterController () + { + } + +-btPairCachingGhostObject* btKinematicCharacterController::getGhostObject() ++btGhostObject* btKinematicCharacterController::getGhostObject() + { + return m_ghostObject; + } +@@ -194,26 +194,32 @@ bool btKinematicCharacterController::recoverFromPenetration ( btCollisionWorld* + + bool penetration = false; + +- collisionWorld->getDispatcher()->dispatchAllCollisionPairs(m_ghostObject->getOverlappingPairCache(), collisionWorld->getDispatchInfo(), collisionWorld->getDispatcher()); +- + m_currentPosition = m_ghostObject->getWorldTransform().getOrigin(); +- ++ ++ btOverlappingPairCache *pairCache = collisionWorld->getPairCache(); ++ const unsigned int numPairs = m_ghostObject->getNumOverlappingObjects(); ++ + // btScalar maxPen = btScalar(0.0); +- for (int i = 0; i < m_ghostObject->getOverlappingPairCache()->getNumOverlappingPairs(); i++) ++ for (int i = 0; i < numPairs; i++) + { +- m_manifoldArray.resize(0); ++ btCollisionObject *obj0 = m_ghostObject; ++ btCollisionObject *obj1 = m_ghostObject->getOverlappingObject(i); + +- btBroadphasePair* collisionPair = &m_ghostObject->getOverlappingPairCache()->getOverlappingPairArray()[i]; ++ btBroadphaseProxy *proxy0 = obj0->getBroadphaseHandle(); ++ btBroadphaseProxy *proxy1 = obj1->getBroadphaseHandle(); + +- btCollisionObject* obj0 = static_cast(collisionPair->m_pProxy0->m_clientObject); +- btCollisionObject* obj1 = static_cast(collisionPair->m_pProxy1->m_clientObject); ++ btBroadphasePair* collisionPair = pairCache->findPair(proxy0, proxy1); ++ ++ btAssert(collisionPair); + + if ((obj0 && !obj0->hasContactResponse()) || (obj1 && !obj1->hasContactResponse())) + continue; + + if (!needsCollision(obj0, obj1)) + continue; +- ++ ++ m_manifoldArray.resize(0); ++ + if (collisionPair->m_algorithm) + collisionPair->m_algorithm->getAllContactManifolds(m_manifoldArray); + +@@ -688,11 +694,11 @@ void btKinematicCharacterController::reset ( btCollisionWorld* collisionWorld ) + m_velocityTimeInterval = 0.0; + + //clear pair cache +- btHashedOverlappingPairCache *cache = m_ghostObject->getOverlappingPairCache(); ++ /*btHashedOverlappingPairCache *cache = m_ghostObject->getOverlappingPairCache(); + while (cache->getOverlappingPairArray().size() > 0) + { + cache->removeOverlappingPair(cache->getOverlappingPairArray()[0].m_pProxy0, cache->getOverlappingPairArray()[0].m_pProxy1, collisionWorld->getDispatcher()); +- } ++ }*/ + } + + void btKinematicCharacterController::warp (const btVector3& origin) +diff --git a/extern/bullet/src/BulletDynamics/Character/btKinematicCharacterController.h b/extern/bullet/src/BulletDynamics/Character/btKinematicCharacterController.h +index 3d677e647e2..2dd12eaa5f1 100644 +--- a/extern/bullet/src/BulletDynamics/Character/btKinematicCharacterController.h ++++ b/extern/bullet/src/BulletDynamics/Character/btKinematicCharacterController.h +@@ -29,7 +29,7 @@ class btConvexShape; + class btRigidBody; + class btCollisionWorld; + class btCollisionDispatcher; +-class btPairCachingGhostObject; ++class btGhostObject; + + ///btKinematicCharacterController is an object that supports a sliding motion in a world. + ///It uses a ghost object and convex sweep test to test for upcoming collisions. This is combined with discrete collision detection to recover from penetrations. +@@ -40,7 +40,7 @@ protected: + + btScalar m_halfHeight; + +- btPairCachingGhostObject* m_ghostObject; ++ btGhostObject* m_ghostObject; + btConvexShape* m_convexShape;//is also in m_ghostObject, but it needs to be convex, so we store it here to avoid upcast + + btScalar m_maxPenetrationDepth; +@@ -117,7 +117,7 @@ public: + + BT_DECLARE_ALIGNED_ALLOCATOR(); + +- btKinematicCharacterController (btPairCachingGhostObject* ghostObject,btConvexShape* convexShape,btScalar stepHeight, const btVector3& up = btVector3(1.0,0.0,0.0)); ++ btKinematicCharacterController (btGhostObject* ghostObject,btConvexShape* convexShape,btScalar stepHeight, const btVector3& up = btVector3(1.0,0.0,0.0)); + ~btKinematicCharacterController (); + + +@@ -191,7 +191,7 @@ public: + void setMaxPenetrationDepth(btScalar d); + btScalar getMaxPenetrationDepth() const; + +- btPairCachingGhostObject* getGhostObject(); ++ btGhostObject* getGhostObject(); + void setUseGhostSweepTest(bool useGhostObjectSweepTest) + { + m_useGhostObjectSweepTest = useGhostObjectSweepTest; +-- +2.18.0 + diff --git a/extern/bullet/patches/softrigid-world-mt.patch b/extern/bullet/patches/softrigid-world-mt.patch new file mode 100644 index 000000000000..0cc37cbd0d93 --- /dev/null +++ b/extern/bullet/patches/softrigid-world-mt.patch @@ -0,0 +1,501 @@ +From 02c5a7ccf91a1ad0c29ae1b181f19713892f5d05 Mon Sep 17 00:00:00 2001 +From: tristan +Date: Fri, 12 Oct 2018 19:16:04 +0200 +Subject: [PATCH] temp + +--- + .../btSoftRigidDynamicsWorldMt.cpp | 367 ++++++++++++++++++ + .../btSoftRigidDynamicsWorldMt.h | 107 +++++ + 2 files changed, 474 insertions(+) + create mode 100644 extern/bullet/src/BulletSoftBody/btSoftRigidDynamicsWorldMt.cpp + create mode 100644 extern/bullet/src/BulletSoftBody/btSoftRigidDynamicsWorldMt.h + +diff --git a/extern/bullet/src/BulletSoftBody/btSoftRigidDynamicsWorldMt.cpp b/extern/bullet/src/BulletSoftBody/btSoftRigidDynamicsWorldMt.cpp +new file mode 100644 +index 00000000000..bd3625a751c +--- /dev/null ++++ b/extern/bullet/src/BulletSoftBody/btSoftRigidDynamicsWorldMt.cpp +@@ -0,0 +1,367 @@ ++/* ++Bullet Continuous Collision Detection and Physics Library ++Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ ++ ++This software is provided 'as-is', without any express or implied warranty. ++In no event will the authors be held liable for any damages arising from the use of this software. ++Permission is granted to anyone to use this software for any purpose, ++including commercial applications, and to alter it and redistribute it freely, ++subject to the following restrictions: ++ ++1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. ++2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. ++3. This notice may not be removed or altered from any source distribution. ++*/ ++ ++ ++#include "btSoftRigidDynamicsWorldMt.h" ++#include "LinearMath/btQuickprof.h" ++ ++//softbody & helpers ++#include "btSoftBody.h" ++#include "btSoftBodyHelpers.h" ++#include "btSoftBodySolvers.h" ++#include "btDefaultSoftBodySolver.h" ++#include "LinearMath/btSerializer.h" ++ ++ ++btSoftRigidDynamicsWorldMt::btSoftRigidDynamicsWorldMt( ++ btDispatcher* dispatcher, ++ btBroadphaseInterface* pairCache, ++ btConstraintSolverPoolMt* constraintSolver, ++ btCollisionConfiguration* collisionConfiguration, ++ btSoftBodySolver *softBodySolver ) : ++ btDiscreteDynamicsWorldMt(dispatcher,pairCache,constraintSolver,collisionConfiguration), ++ m_softBodySolver( softBodySolver ), ++ m_ownsSolver(false) ++{ ++ if( !m_softBodySolver ) ++ { ++ void* ptr = btAlignedAlloc(sizeof(btDefaultSoftBodySolver),16); ++ m_softBodySolver = new(ptr) btDefaultSoftBodySolver(); ++ m_ownsSolver = true; ++ } ++ ++ m_drawFlags = fDrawFlags::Std; ++ m_drawNodeTree = true; ++ m_drawFaceTree = false; ++ m_drawClusterTree = false; ++ m_sbi.m_broadphase = pairCache; ++ m_sbi.m_dispatcher = dispatcher; ++ m_sbi.m_sparsesdf.Initialize(); ++ m_sbi.m_sparsesdf.Reset(); ++ ++ m_sbi.air_density = (btScalar)1.2; ++ m_sbi.water_density = 0; ++ m_sbi.water_offset = 0; ++ m_sbi.water_normal = btVector3(0,0,0); ++ m_sbi.m_gravity.setValue(0,-10,0); ++ ++ m_sbi.m_sparsesdf.Initialize(); ++ ++ ++} ++ ++btSoftRigidDynamicsWorldMt::~btSoftRigidDynamicsWorldMt() ++{ ++ if (m_ownsSolver) ++ { ++ m_softBodySolver->~btSoftBodySolver(); ++ btAlignedFree(m_softBodySolver); ++ } ++} ++ ++void btSoftRigidDynamicsWorldMt::predictUnconstraintMotion(btScalar timeStep) ++{ ++ btDiscreteDynamicsWorldMt::predictUnconstraintMotion( timeStep ); ++ { ++ BT_PROFILE("predictUnconstraintMotionSoftBody"); ++ m_softBodySolver->predictMotion( float(timeStep) ); ++ } ++} ++ ++void btSoftRigidDynamicsWorldMt::internalSingleStepSimulation( btScalar timeStep ) ++{ ++ ++ // Let the solver grab the soft bodies and if necessary optimize for it ++ m_softBodySolver->optimize( getSoftBodyArray() ); ++ ++ if( !m_softBodySolver->checkInitialized() ) ++ { ++ btAssert( "Solver initialization failed\n" ); ++ } ++ ++ btDiscreteDynamicsWorldMt::internalSingleStepSimulation( timeStep ); ++ ++ ///solve soft bodies constraints ++ solveSoftBodiesConstraints( timeStep ); ++ ++ //self collisions ++ for ( int i=0;idefaultCollisionHandler(psb); ++ } ++ ++ ///update soft bodies ++ m_softBodySolver->updateSoftBodies( ); ++ ++ // End solver-wise simulation step ++ // /////////////////////////////// ++ ++} ++ ++void btSoftRigidDynamicsWorldMt::solveSoftBodiesConstraints( btScalar timeStep ) ++{ ++ BT_PROFILE("solveSoftConstraints"); ++ ++ if(m_softBodies.size()) ++ { ++ btSoftBody::solveClusters(m_softBodies); ++ } ++ ++ // Solve constraints solver-wise ++ m_softBodySolver->solveConstraints( timeStep * m_softBodySolver->getTimeScale() ); ++ ++} ++ ++void btSoftRigidDynamicsWorldMt::addSoftBody(btSoftBody* body, int collisionFilterGroup, int collisionFilterMask) ++{ ++ m_softBodies.push_back(body); ++ ++ // Set the soft body solver that will deal with this body ++ // to be the world's solver ++ body->setSoftBodySolver( m_softBodySolver ); ++ ++ btCollisionWorld::addCollisionObject(body, ++ collisionFilterGroup, ++ collisionFilterMask); ++ ++} ++ ++void btSoftRigidDynamicsWorldMt::removeSoftBody(btSoftBody* body) ++{ ++ m_softBodies.remove(body); ++ ++ btCollisionWorld::removeCollisionObject(body); ++} ++ ++void btSoftRigidDynamicsWorldMt::removeCollisionObject(btCollisionObject* collisionObject) ++{ ++ btSoftBody* body = btSoftBody::upcast(collisionObject); ++ if (body) ++ removeSoftBody(body); ++ else ++ btDiscreteDynamicsWorldMt::removeCollisionObject(collisionObject); ++} ++ ++void btSoftRigidDynamicsWorldMt::debugDrawWorld() ++{ ++ btDiscreteDynamicsWorldMt::debugDrawWorld(); ++ ++ if (getDebugDrawer()) ++ { ++ int i; ++ for ( i=0;im_softBodies.size();i++) ++ { ++ btSoftBody* psb=(btSoftBody*)this->m_softBodies[i]; ++ if (getDebugDrawer() && (getDebugDrawer()->getDebugMode() & (btIDebugDraw::DBG_DrawWireframe))) ++ { ++ btSoftBodyHelpers::DrawFrame(psb,m_debugDrawer); ++ btSoftBodyHelpers::Draw(psb,m_debugDrawer,m_drawFlags); ++ } ++ ++ if (m_debugDrawer && (m_debugDrawer->getDebugMode() & btIDebugDraw::DBG_DrawAabb)) ++ { ++ if(m_drawNodeTree) btSoftBodyHelpers::DrawNodeTree(psb,m_debugDrawer); ++ if(m_drawFaceTree) btSoftBodyHelpers::DrawFaceTree(psb,m_debugDrawer); ++ if(m_drawClusterTree) btSoftBodyHelpers::DrawClusterTree(psb,m_debugDrawer); ++ } ++ } ++ } ++} ++ ++ ++ ++ ++struct btSoftSingleRayCallback : public btBroadphaseRayCallback ++{ ++ btVector3 m_rayFromWorld; ++ btVector3 m_rayToWorld; ++ btTransform m_rayFromTrans; ++ btTransform m_rayToTrans; ++ btVector3 m_hitNormal; ++ ++ const btSoftRigidDynamicsWorldMt* m_world; ++ btCollisionWorld::RayResultCallback& m_resultCallback; ++ ++ btSoftSingleRayCallback(const btVector3& rayFromWorld,const btVector3& rayToWorld,const btSoftRigidDynamicsWorldMt* world,btCollisionWorld::RayResultCallback& resultCallback) ++ :m_rayFromWorld(rayFromWorld), ++ m_rayToWorld(rayToWorld), ++ m_world(world), ++ m_resultCallback(resultCallback) ++ { ++ m_rayFromTrans.setIdentity(); ++ m_rayFromTrans.setOrigin(m_rayFromWorld); ++ m_rayToTrans.setIdentity(); ++ m_rayToTrans.setOrigin(m_rayToWorld); ++ ++ btVector3 rayDir = (rayToWorld-rayFromWorld); ++ ++ rayDir.normalize (); ++ ///what about division by zero? --> just set rayDirection[i] to INF/1e30 ++ m_rayDirectionInverse[0] = rayDir[0] == btScalar(0.0) ? btScalar(1e30) : btScalar(1.0) / rayDir[0]; ++ m_rayDirectionInverse[1] = rayDir[1] == btScalar(0.0) ? btScalar(1e30) : btScalar(1.0) / rayDir[1]; ++ m_rayDirectionInverse[2] = rayDir[2] == btScalar(0.0) ? btScalar(1e30) : btScalar(1.0) / rayDir[2]; ++ m_signs[0] = m_rayDirectionInverse[0] < 0.0; ++ m_signs[1] = m_rayDirectionInverse[1] < 0.0; ++ m_signs[2] = m_rayDirectionInverse[2] < 0.0; ++ ++ m_lambda_max = rayDir.dot(m_rayToWorld-m_rayFromWorld); ++ ++ } ++ ++ ++ ++ virtual bool process(const btBroadphaseProxy* proxy) ++ { ++ ///terminate further ray tests, once the closestHitFraction reached zero ++ if (m_resultCallback.m_closestHitFraction == btScalar(0.f)) ++ return false; ++ ++ btCollisionObject* collisionObject = (btCollisionObject*)proxy->m_clientObject; ++ ++ //only perform raycast if filterMask matches ++ if(m_resultCallback.needsCollision(collisionObject->getBroadphaseHandle())) ++ { ++ //RigidcollisionObject* collisionObject = ctrl->GetRigidcollisionObject(); ++ //btVector3 collisionObjectAabbMin,collisionObjectAabbMax; ++#if 0 ++#ifdef RECALCULATE_AABB ++ btVector3 collisionObjectAabbMin,collisionObjectAabbMax; ++ collisionObject->getCollisionShape()->getAabb(collisionObject->getWorldTransform(),collisionObjectAabbMin,collisionObjectAabbMax); ++#else ++ //getBroadphase()->getAabb(collisionObject->getBroadphaseHandle(),collisionObjectAabbMin,collisionObjectAabbMax); ++ const btVector3& collisionObjectAabbMin = collisionObject->getBroadphaseHandle()->m_aabbMin; ++ const btVector3& collisionObjectAabbMax = collisionObject->getBroadphaseHandle()->m_aabbMax; ++#endif ++#endif ++ //btScalar hitLambda = m_resultCallback.m_closestHitFraction; ++ //culling already done by broadphase ++ //if (btRayAabb(m_rayFromWorld,m_rayToWorld,collisionObjectAabbMin,collisionObjectAabbMax,hitLambda,m_hitNormal)) ++ { ++ m_world->rayTestSingle(m_rayFromTrans,m_rayToTrans, ++ collisionObject, ++ collisionObject->getCollisionShape(), ++ collisionObject->getWorldTransform(), ++ m_resultCallback); ++ } ++ } ++ return true; ++ } ++}; ++ ++void btSoftRigidDynamicsWorldMt::rayTest(const btVector3& rayFromWorld, const btVector3& rayToWorld, RayResultCallback& resultCallback) const ++{ ++ BT_PROFILE("rayTest"); ++ /// use the broadphase to accelerate the search for objects, based on their aabb ++ /// and for each object with ray-aabb overlap, perform an exact ray test ++ btSoftSingleRayCallback rayCB(rayFromWorld,rayToWorld,this,resultCallback); ++ ++#ifndef USE_BRUTEFORCE_RAYBROADPHASE ++ m_broadphasePairCache->rayTest(rayFromWorld,rayToWorld,rayCB); ++#else ++ for (int i=0;igetNumCollisionObjects();i++) ++ { ++ rayCB.process(m_collisionObjects[i]->getBroadphaseHandle()); ++ } ++#endif //USE_BRUTEFORCE_RAYBROADPHASE ++ ++} ++ ++ ++void btSoftRigidDynamicsWorldMt::rayTestSingle(const btTransform& rayFromTrans,const btTransform& rayToTrans, ++ btCollisionObject* collisionObject, ++ const btCollisionShape* collisionShape, ++ const btTransform& colObjWorldTransform, ++ RayResultCallback& resultCallback) ++{ ++ if (collisionShape->isSoftBody()) { ++ btSoftBody* softBody = btSoftBody::upcast(collisionObject); ++ if (softBody) { ++ btSoftBody::sRayCast softResult; ++ if (softBody->rayTest(rayFromTrans.getOrigin(), rayToTrans.getOrigin(), softResult)) ++ { ++ ++ if (softResult.fraction<= resultCallback.m_closestHitFraction) ++ { ++ ++ btCollisionWorld::LocalShapeInfo shapeInfo; ++ shapeInfo.m_shapePart = 0; ++ shapeInfo.m_triangleIndex = softResult.index; ++ // get the normal ++ btVector3 rayDir = rayToTrans.getOrigin() - rayFromTrans.getOrigin(); ++ btVector3 normal=-rayDir; ++ normal.normalize(); ++ ++ if (softResult.feature == btSoftBody::eFeature::Face) ++ { ++ normal = softBody->m_faces[softResult.index].m_normal; ++ if (normal.dot(rayDir) > 0) { ++ // normal always point toward origin of the ray ++ normal = -normal; ++ } ++ } ++ ++ btCollisionWorld::LocalRayResult rayResult ++ (collisionObject, ++ &shapeInfo, ++ normal, ++ softResult.fraction); ++ bool normalInWorldSpace = true; ++ resultCallback.addSingleResult(rayResult,normalInWorldSpace); ++ } ++ } ++ } ++ } ++ else { ++ btCollisionWorld::rayTestSingle(rayFromTrans,rayToTrans,collisionObject,collisionShape,colObjWorldTransform,resultCallback); ++ } ++} ++ ++ ++void btSoftRigidDynamicsWorldMt::serializeSoftBodies(btSerializer* serializer) ++{ ++ int i; ++ //serialize all collision objects ++ for (i=0;igetInternalType() & btCollisionObject::CO_SOFT_BODY) ++ { ++ int len = colObj->calculateSerializeBufferSize(); ++ btChunk* chunk = serializer->allocate(len,1); ++ const char* structType = colObj->serialize(chunk->m_oldPtr, serializer); ++ serializer->finalizeChunk(chunk,structType,BT_SOFTBODY_CODE,colObj); ++ } ++ } ++ ++} ++ ++void btSoftRigidDynamicsWorldMt::serialize(btSerializer* serializer) ++{ ++ ++ serializer->startSerialization(); ++ ++ serializeDynamicsWorldInfo( serializer); ++ ++ serializeSoftBodies(serializer); ++ ++ serializeRigidBodies(serializer); ++ ++ serializeCollisionObjects(serializer); ++ ++ serializer->finishSerialization(); ++} ++ ++ +diff --git a/extern/bullet/src/BulletSoftBody/btSoftRigidDynamicsWorldMt.h b/extern/bullet/src/BulletSoftBody/btSoftRigidDynamicsWorldMt.h +new file mode 100644 +index 00000000000..be3b98c3361 +--- /dev/null ++++ b/extern/bullet/src/BulletSoftBody/btSoftRigidDynamicsWorldMt.h +@@ -0,0 +1,107 @@ ++/* ++Bullet Continuous Collision Detection and Physics Library ++Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ ++ ++This software is provided 'as-is', without any express or implied warranty. ++In no event will the authors be held liable for any damages arising from the use of this software. ++Permission is granted to anyone to use this software for any purpose, ++including commercial applications, and to alter it and redistribute it freely, ++subject to the following restrictions: ++ ++1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. ++2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. ++3. This notice may not be removed or altered from any source distribution. ++*/ ++ ++#ifndef BT_SOFT_RIGID_DYNAMICS_WORLD_H ++#define BT_SOFT_RIGID_DYNAMICS_WORLD_H ++ ++#include "BulletDynamics/Dynamics/btDiscreteDynamicsWorldMt.h" ++#include "btSoftBody.h" ++ ++typedef btAlignedObjectArray btSoftBodyArray; ++ ++class btSoftBodySolver; ++ ++class btSoftRigidDynamicsWorldMt : public btDiscreteDynamicsWorldMt ++{ ++ ++ btSoftBodyArray m_softBodies; ++ int m_drawFlags; ++ bool m_drawNodeTree; ++ bool m_drawFaceTree; ++ bool m_drawClusterTree; ++ btSoftBodyWorldInfo m_sbi; ++ ///Solver classes that encapsulate multiple soft bodies for solving ++ btSoftBodySolver *m_softBodySolver; ++ bool m_ownsSolver; ++ ++protected: ++ ++ virtual void predictUnconstraintMotion(btScalar timeStep); ++ ++ virtual void internalSingleStepSimulation( btScalar timeStep); ++ ++ void solveSoftBodiesConstraints( btScalar timeStep ); ++ ++ void serializeSoftBodies(btSerializer* serializer); ++ ++public: ++ ++ btSoftRigidDynamicsWorldMt(btDispatcher* dispatcher,btBroadphaseInterface* pairCache,btConstraintSolverPoolMt* constraintSolver, btCollisionConfiguration* collisionConfiguration, btSoftBodySolver *softBodySolver = 0 ); ++ ++ virtual ~btSoftRigidDynamicsWorldMt(); ++ ++ virtual void debugDrawWorld(); ++ ++ void addSoftBody(btSoftBody* body, int collisionFilterGroup=btBroadphaseProxy::DefaultFilter, int collisionFilterMask=btBroadphaseProxy::AllFilter); ++ ++ void removeSoftBody(btSoftBody* body); ++ ++ ///removeCollisionObject will first check if it is a rigid body, if so call removeRigidBody otherwise call btDiscreteDynamicsWorld::removeCollisionObject ++ virtual void removeCollisionObject(btCollisionObject* collisionObject); ++ ++ int getDrawFlags() const { return(m_drawFlags); } ++ void setDrawFlags(int f) { m_drawFlags=f; } ++ ++ btSoftBodyWorldInfo& getWorldInfo() ++ { ++ return m_sbi; ++ } ++ const btSoftBodyWorldInfo& getWorldInfo() const ++ { ++ return m_sbi; ++ } ++ ++ virtual btDynamicsWorldType getWorldType() const ++ { ++ return BT_SOFT_RIGID_DYNAMICS_WORLD; ++ } ++ ++ btSoftBodyArray& getSoftBodyArray() ++ { ++ return m_softBodies; ++ } ++ ++ const btSoftBodyArray& getSoftBodyArray() const ++ { ++ return m_softBodies; ++ } ++ ++ ++ virtual void rayTest(const btVector3& rayFromWorld, const btVector3& rayToWorld, RayResultCallback& resultCallback) const; ++ ++ /// rayTestSingle performs a raycast call and calls the resultCallback. It is used internally by rayTest. ++ /// In a future implementation, we consider moving the ray test as a virtual method in btCollisionShape. ++ /// This allows more customization. ++ static void rayTestSingle(const btTransform& rayFromTrans,const btTransform& rayToTrans, ++ btCollisionObject* collisionObject, ++ const btCollisionShape* collisionShape, ++ const btTransform& colObjWorldTransform, ++ RayResultCallback& resultCallback); ++ ++ virtual void serialize(btSerializer* serializer); ++ ++}; ++ ++#endif //BT_SOFT_RIGID_DYNAMICS_WORLD_H +-- +2.18.0 + diff --git a/extern/bullet/src/Bullet3Collision/premake4.lua b/extern/bullet/src/Bullet3Collision/premake4.lua index bd0da541ec19..0b47f8ea5b83 100644 --- a/extern/bullet/src/Bullet3Collision/premake4.lua +++ b/extern/bullet/src/Bullet3Collision/premake4.lua @@ -6,9 +6,6 @@ includedirs {".."} - if os.is("Linux") then - buildoptions{"-fPIC"} - end files { "**.cpp", diff --git a/extern/bullet/src/Bullet3Common/b3AlignedObjectArray.h b/extern/bullet/src/Bullet3Common/b3AlignedObjectArray.h index ef71016565ac..947362d08ecc 100644 --- a/extern/bullet/src/Bullet3Common/b3AlignedObjectArray.h +++ b/extern/bullet/src/Bullet3Common/b3AlignedObjectArray.h @@ -528,14 +528,6 @@ class b3AlignedObjectArray otherArray.copy(0, otherSize, m_data); } - void removeAtIndex(int index) - { - if (indexfps * limot->m_stopERP); info->m_constraintError[srow] += mot_fact * limot->m_targetVelocity; - info->m_lowerLimit[srow] = -limot->m_maxMotorForce / info->fps; - info->m_upperLimit[srow] = limot->m_maxMotorForce / info->fps; + info->m_lowerLimit[srow] = -limot->m_maxMotorForce; + info->m_upperLimit[srow] = limot->m_maxMotorForce; } } if(limit) diff --git a/extern/bullet/src/Bullet3Dynamics/ConstraintSolver/b3Generic6DofConstraint.h b/extern/bullet/src/Bullet3Dynamics/ConstraintSolver/b3Generic6DofConstraint.h index 169b1b94ade6..084d36055ccc 100644 --- a/extern/bullet/src/Bullet3Dynamics/ConstraintSolver/b3Generic6DofConstraint.h +++ b/extern/bullet/src/Bullet3Dynamics/ConstraintSolver/b3Generic6DofConstraint.h @@ -69,7 +69,7 @@ class b3RotationalLimitMotor { m_accumulatedImpulse = 0.f; m_targetVelocity = 0; - m_maxMotorForce = 6.0f; + m_maxMotorForce = 0.1f; m_maxLimitForce = 300.0f; m_loLimit = 1.0f; m_hiLimit = -1.0f; diff --git a/extern/bullet/src/Bullet3Dynamics/premake4.lua b/extern/bullet/src/Bullet3Dynamics/premake4.lua index e05b2cd19486..669336a6a1d2 100644 --- a/extern/bullet/src/Bullet3Dynamics/premake4.lua +++ b/extern/bullet/src/Bullet3Dynamics/premake4.lua @@ -8,9 +8,6 @@ ".." } - if os.is("Linux") then - buildoptions{"-fPIC"} - end files { "**.cpp", diff --git a/extern/bullet/src/Bullet3Geometry/premake4.lua b/extern/bullet/src/Bullet3Geometry/premake4.lua index cce93f7ee1d9..1a230f8c0101 100644 --- a/extern/bullet/src/Bullet3Geometry/premake4.lua +++ b/extern/bullet/src/Bullet3Geometry/premake4.lua @@ -6,9 +6,6 @@ includedirs {".."} - if os.is("Linux") then - buildoptions{"-fPIC"} - end files { "**.cpp", diff --git a/extern/bullet/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp b/extern/bullet/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp index 896191c89c9e..dd194fc7ba76 100644 --- a/extern/bullet/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp +++ b/extern/bullet/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp @@ -619,7 +619,7 @@ cl_program b3OpenCLUtils_compileCLProgramFromString(cl_context clContext, cl_dev strippedName = strip2(clFileNameForCaching,"\\"); strippedName = strip2(strippedName,"/"); -#ifdef _MSC_VER +#ifdef _MSVC_VER sprintf_s(binaryFileName,B3_MAX_STRING_LENGTH,"%s/%s.%s.%s.bin",sCachedBinaryPath,strippedName, deviceName,driverVersion ); #else sprintf(binaryFileName,"%s/%s.%s.%s.bin",sCachedBinaryPath,strippedName, deviceName,driverVersion ); diff --git a/extern/bullet/src/Bullet3OpenCL/premake4.lua b/extern/bullet/src/Bullet3OpenCL/premake4.lua index ee35fdb522ab..55a861363485 100644 --- a/extern/bullet/src/Bullet3OpenCL/premake4.lua +++ b/extern/bullet/src/Bullet3OpenCL/premake4.lua @@ -9,9 +9,6 @@ function createProject(vendor) kind "StaticLib" - if os.is("Linux") then - buildoptions{"-fPIC"} - end includedirs { ".",".." diff --git a/extern/bullet/src/Bullet3Serialize/Bullet2FileLoader/premake4.lua b/extern/bullet/src/Bullet3Serialize/Bullet2FileLoader/premake4.lua index b9ee301befa0..ec2f0a51ae7a 100644 --- a/extern/bullet/src/Bullet3Serialize/Bullet2FileLoader/premake4.lua +++ b/extern/bullet/src/Bullet3Serialize/Bullet2FileLoader/premake4.lua @@ -5,10 +5,6 @@ includedirs { "../../../src" } - - if os.is("Linux") then - buildoptions{"-fPIC"} - end files { "**.cpp", diff --git a/extern/bullet/src/BulletCollision/BroadphaseCollision/btAxisSweep3Internal.h b/extern/bullet/src/BulletCollision/BroadphaseCollision/btAxisSweep3Internal.h index 323aa96dcac6..2c4d41bc041b 100644 --- a/extern/bullet/src/BulletCollision/BroadphaseCollision/btAxisSweep3Internal.h +++ b/extern/bullet/src/BulletCollision/BroadphaseCollision/btAxisSweep3Internal.h @@ -628,6 +628,7 @@ void btAxisSweep3Internal::resetPool(btDispatcher* /*dispatcher* } +extern int gOverlappingPairs; //#include template @@ -694,9 +695,10 @@ void btAxisSweep3Internal::calculateOverlappingPairs(btDispatche pair.m_pProxy0 = 0; pair.m_pProxy1 = 0; m_invalidPair++; - } - - } + gOverlappingPairs--; + } + + } ///if you don't like to skip the invalid pairs in the array, execute following code: #define CLEAN_INVALID_PAIRS 1 diff --git a/extern/bullet/src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.h b/extern/bullet/src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.h index f6e1202a697d..adaf083a21dc 100644 --- a/extern/bullet/src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.h +++ b/extern/bullet/src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.h @@ -66,7 +66,6 @@ CONCAVE_SHAPES_START_HERE, EMPTY_SHAPE_PROXYTYPE, STATIC_PLANE_PROXYTYPE, CUSTOM_CONCAVE_SHAPE_TYPE, - SDF_SHAPE_PROXYTYPE=CUSTOM_CONCAVE_SHAPE_TYPE, CONCAVE_SHAPES_END_HERE, COMPOUND_SHAPE_PROXYTYPE, diff --git a/extern/bullet/src/BulletCollision/BroadphaseCollision/btDispatcher.h b/extern/bullet/src/BulletCollision/BroadphaseCollision/btDispatcher.h index a0e4c189270a..7b0f9489afd5 100644 --- a/extern/bullet/src/BulletCollision/BroadphaseCollision/btDispatcher.h +++ b/extern/bullet/src/BulletCollision/BroadphaseCollision/btDispatcher.h @@ -46,8 +46,7 @@ struct btDispatcherInfo m_useEpa(true), m_allowedCcdPenetration(btScalar(0.04)), m_useConvexConservativeDistanceUtil(false), - m_convexConservativeDistanceThreshold(0.0f), - m_deterministicOverlappingPairs(false) + m_convexConservativeDistanceThreshold(0.0f) { } @@ -63,7 +62,6 @@ struct btDispatcherInfo btScalar m_allowedCcdPenetration; bool m_useConvexConservativeDistanceUtil; btScalar m_convexConservativeDistanceThreshold; - bool m_deterministicOverlappingPairs; }; enum ebtDispatcherQueryType diff --git a/extern/bullet/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.cpp b/extern/bullet/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.cpp index 9e3337c5f65b..55ebf06f1e5f 100644 --- a/extern/bullet/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.cpp +++ b/extern/bullet/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.cpp @@ -23,6 +23,11 @@ subject to the following restrictions: #include +int gOverlappingPairs = 0; + +int gRemovePairs =0; +int gAddedPairs =0; +int gFindPairs =0; @@ -129,12 +134,13 @@ void btHashedOverlappingPairCache::removeOverlappingPairsContainingProxy(btBroad btBroadphasePair* btHashedOverlappingPairCache::findPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1) { - if(proxy0->m_uniqueId>proxy1->m_uniqueId) + gFindPairs++; + if(proxy0->m_uniqueId>proxy1->m_uniqueId) btSwap(proxy0,proxy1); int proxyId1 = proxy0->getUid(); int proxyId2 = proxy1->getUid(); - /*if (proxyId1 > proxyId2) + /*if (proxyId1 > proxyId2) btSwap(proxyId1, proxyId2);*/ int hash = static_cast(getHash(static_cast(proxyId1), static_cast(proxyId2)) & (m_overlappingPairArray.capacity()-1)); @@ -265,12 +271,13 @@ btBroadphasePair* btHashedOverlappingPairCache::internalAddPair(btBroadphaseProx void* btHashedOverlappingPairCache::removeOverlappingPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1,btDispatcher* dispatcher) { - if(proxy0->m_uniqueId>proxy1->m_uniqueId) + gRemovePairs++; + if(proxy0->m_uniqueId>proxy1->m_uniqueId) btSwap(proxy0,proxy1); int proxyId1 = proxy0->getUid(); int proxyId2 = proxy1->getUid(); - /*if (proxyId1 > proxyId2) + /*if (proxyId1 > proxyId2) btSwap(proxyId1, proxyId2);*/ int hash = static_cast(getHash(static_cast(proxyId1),static_cast(proxyId2)) & (m_overlappingPairArray.capacity()-1)); @@ -379,6 +386,8 @@ void btHashedOverlappingPairCache::processAllOverlappingPairs(btOverlapCallback* if (callback->processOverlap(*pair)) { removeOverlappingPair(pair->m_pProxy0,pair->m_pProxy1,dispatcher); + + gOverlappingPairs--; } else { i++; @@ -386,70 +395,6 @@ void btHashedOverlappingPairCache::processAllOverlappingPairs(btOverlapCallback* } } -struct MyPairIndex -{ - int m_orgIndex; - int m_uidA0; - int m_uidA1; -}; - -class MyPairIndeSortPredicate -{ -public: - - bool operator() ( const MyPairIndex& a, const MyPairIndex& b ) const - { - const int uidA0 = a.m_uidA0; - const int uidB0 = b.m_uidA0; - const int uidA1 = a.m_uidA1; - const int uidB1 = b.m_uidA1; - return uidA0 > uidB0 || (uidA0 == uidB0 && uidA1 > uidB1); - } -}; - -void btHashedOverlappingPairCache::processAllOverlappingPairs(btOverlapCallback* callback,btDispatcher* dispatcher, const struct btDispatcherInfo& dispatchInfo) -{ - if (dispatchInfo.m_deterministicOverlappingPairs) - { - btBroadphasePairArray& pa = getOverlappingPairArray(); - btAlignedObjectArray indices; - { - BT_PROFILE("sortOverlappingPairs"); - indices.resize(pa.size()); - for (int i=0;im_uniqueId : -1; - const int uidA1 = p.m_pProxy1 ? p.m_pProxy1->m_uniqueId : -1; - - indices[i].m_uidA0 = uidA0; - indices[i].m_uidA1 = uidA1; - indices[i].m_orgIndex = i; - } - indices.quickSort(MyPairIndeSortPredicate()); - } - { - BT_PROFILE("btHashedOverlappingPairCache::processAllOverlappingPairs"); - int i; - for (i=0;iprocessOverlap(*pair)) - { - removeOverlappingPair(pair->m_pProxy0,pair->m_pProxy1,dispatcher); - } else - { - i++; - } - } - } - } else - { - processAllOverlappingPairs(callback, dispatcher); - } -} - - void btHashedOverlappingPairCache::sortOverlappingPairs(btDispatcher* dispatcher) { ///need to keep hashmap in sync with pair address, so rebuild all @@ -490,6 +435,7 @@ void* btSortedOverlappingPairCache::removeOverlappingPair(btBroadphaseProxy* pro int findIndex = m_overlappingPairArray.findLinearSearch(findPair); if (findIndex < m_overlappingPairArray.size()) { + gOverlappingPairs--; btBroadphasePair& pair = m_overlappingPairArray[findIndex]; void* userData = pair.m_internalInfo1; cleanOverlappingPair(pair,dispatcher); @@ -522,8 +468,11 @@ btBroadphasePair* btSortedOverlappingPairCache::addOverlappingPair(btBroadphaseP void* mem = &m_overlappingPairArray.expandNonInitializing(); btBroadphasePair* pair = new (mem) btBroadphasePair(*proxy0,*proxy1); - - if (m_ghostPairCallback) + + gOverlappingPairs++; + gAddedPairs++; + + if (m_ghostPairCallback) m_ghostPairCallback->addOverlappingPair(proxy0, proxy1); return pair; @@ -577,6 +526,7 @@ void btSortedOverlappingPairCache::processAllOverlappingPairs(btOverlapCallback* pair->m_pProxy1 = 0; m_overlappingPairArray.swap(i,m_overlappingPairArray.size()-1); m_overlappingPairArray.pop_back(); + gOverlappingPairs--; } else { i++; @@ -609,6 +559,7 @@ void btSortedOverlappingPairCache::cleanOverlappingPair(btBroadphasePair& pair,b pair.m_algorithm->~btCollisionAlgorithm(); dispatcher->freeCollisionAlgorithm(pair.m_algorithm); pair.m_algorithm=0; + gRemovePairs--; } } } diff --git a/extern/bullet/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h b/extern/bullet/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h index 7a38d34f0529..f7be7d45b3e5 100644 --- a/extern/bullet/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h +++ b/extern/bullet/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h @@ -49,6 +49,10 @@ struct btOverlapFilterCallback +extern int gRemovePairs; +extern int gAddedPairs; +extern int gFindPairs; + const int BT_NULL_PAIR=0xffffffff; ///The btOverlappingPairCache provides an interface for overlapping pair management (add, remove, storage), used by the btBroadphaseInterface broadphases. @@ -74,10 +78,6 @@ class btOverlappingPairCache : public btOverlappingPairCallback virtual void processAllOverlappingPairs(btOverlapCallback*,btDispatcher* dispatcher) = 0; - virtual void processAllOverlappingPairs(btOverlapCallback* callback,btDispatcher* dispatcher, const struct btDispatcherInfo& dispatchInfo) - { - processAllOverlappingPairs(callback, dispatcher); - } virtual btBroadphasePair* findPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1) = 0; virtual bool hasDeferredRemoval() = 0; @@ -129,6 +129,8 @@ ATTRIBUTE_ALIGNED16(class) btHashedOverlappingPairCache : public btOverlappingPa // no new pair is created and the old one is returned. virtual btBroadphasePair* addOverlappingPair(btBroadphaseProxy* proxy0,btBroadphaseProxy* proxy1) { + gAddedPairs++; + if (!needsBroadphaseCollision(proxy0,proxy1)) return 0; @@ -142,8 +144,6 @@ ATTRIBUTE_ALIGNED16(class) btHashedOverlappingPairCache : public btOverlappingPa virtual void processAllOverlappingPairs(btOverlapCallback*,btDispatcher* dispatcher); - virtual void processAllOverlappingPairs(btOverlapCallback* callback,btDispatcher* dispatcher, const struct btDispatcherInfo& dispatchInfo); - virtual btBroadphasePair* getOverlappingPairArrayPtr() { return &m_overlappingPairArray[0]; diff --git a/extern/bullet/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.cpp b/extern/bullet/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.cpp index 5f89f960e81f..f1d5f5476ecf 100644 --- a/extern/bullet/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.cpp +++ b/extern/bullet/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.cpp @@ -24,6 +24,8 @@ subject to the following restrictions: #include +extern int gOverlappingPairs; + void btSimpleBroadphase::validate() { for (int i=0;igetNumEdges(); i++) { @@ -142,9 +141,8 @@ bool SphereTriangleDetector::collide(const btVector3& sphereCenter,btVector3 &po m_triangle->getEdge(i, pa, pb); btScalar distanceSqr = SegmentSqrDistance(pa, pb, sphereCenter, nearestOnEdge); - if (distanceSqr < minDistSqr) { - // Yep, we're inside a capsule, and record the capsule with smallest distance - minDistSqr = distanceSqr; + if (distanceSqr < contactCapsuleRadiusSqr) { + // Yep, we're inside a capsule hasContact = true; contactPoint = nearestOnEdge; } diff --git a/extern/bullet/src/BulletCollision/CollisionDispatch/btBox2dBox2dCollisionAlgorithm.cpp b/extern/bullet/src/BulletCollision/CollisionDispatch/btBox2dBox2dCollisionAlgorithm.cpp index cabbb0bf6a04..2c3627782109 100644 --- a/extern/bullet/src/BulletCollision/CollisionDispatch/btBox2dBox2dCollisionAlgorithm.cpp +++ b/extern/bullet/src/BulletCollision/CollisionDispatch/btBox2dBox2dCollisionAlgorithm.cpp @@ -151,8 +151,8 @@ static btScalar EdgeSeparation(const btBox2dShape* poly1, const btTransform& xf1 int index = 0; btScalar minDot = BT_LARGE_FLOAT; - if( count2 > 0 ) - index = (int) normal1.minDot( vertices2, count2, minDot); + if( count2 > 0 ) + index = (int) normal1.minDot( vertices2, count2, minDot); btVector3 v1 = b2Mul(xf1, vertices1[edge1]); btVector3 v2 = b2Mul(xf2, vertices2[index]); @@ -175,8 +175,8 @@ static btScalar FindMaxSeparation(int* edgeIndex, // Find edge normal on poly1 that has the largest projection onto d. int edge = 0; btScalar maxDot; - if( count1 > 0 ) - edge = (int) dLocal1.maxDot( normals1, count1, maxDot); + if( count1 > 0 ) + edge = (int) dLocal1.maxDot( normals1, count1, maxDot); // Get the separation for the edge normal. btScalar s = EdgeSeparation(poly1, xf1, edge, poly2, xf2); diff --git a/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.cpp b/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.cpp index f8794dec47c9..5739a1ef01e1 100644 --- a/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.cpp +++ b/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.cpp @@ -27,6 +27,8 @@ subject to the following restrictions: #include "BulletCollision/CollisionDispatch/btCollisionConfiguration.h" #include "BulletCollision/CollisionDispatch/btCollisionObjectWrapper.h" +int gNumManifold = 0; + #ifdef BT_DEBUG #include #endif @@ -75,6 +77,8 @@ btCollisionDispatcher::~btCollisionDispatcher() btPersistentManifold* btCollisionDispatcher::getNewManifold(const btCollisionObject* body0,const btCollisionObject* body1) { + gNumManifold++; + //btAssert(gNumManifold < 65535); @@ -117,6 +121,7 @@ void btCollisionDispatcher::clearManifold(btPersistentManifold* manifold) void btCollisionDispatcher::releaseManifold(btPersistentManifold* manifold) { + gNumManifold--; //printf("releaseManifold: gNumManifold %d\n",gNumManifold); clearManifold(manifold); @@ -241,17 +246,13 @@ class btCollisionPairCallback : public btOverlapCallback - void btCollisionDispatcher::dispatchAllCollisionPairs(btOverlappingPairCache* pairCache,const btDispatcherInfo& dispatchInfo,btDispatcher* dispatcher) { //m_blockedForChanges = true; btCollisionPairCallback collisionCallback(dispatchInfo,this); - { - BT_PROFILE("processAllOverlappingPairs"); - pairCache->processAllOverlappingPairs(&collisionCallback,dispatcher, dispatchInfo); - } + pairCache->processAllOverlappingPairs(&collisionCallback,dispatcher); //m_blockedForChanges = false; diff --git a/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionObject.cpp b/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionObject.cpp index 05f96a14bc8d..b595c56bc56e 100644 --- a/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionObject.cpp +++ b/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionObject.cpp @@ -16,7 +16,6 @@ subject to the following restrictions: #include "btCollisionObject.h" #include "LinearMath/btSerializer.h" -#include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h" btCollisionObject::btCollisionObject() : m_interpolationLinearVelocity(0.f, 0.f, 0.f), @@ -39,7 +38,7 @@ btCollisionObject::btCollisionObject() m_rollingFriction(0.0f), m_spinningFriction(0.f), m_contactDamping(.1), - m_contactStiffness(BT_LARGE_FLOAT), + m_contactStiffness(1e4), m_internalType(CO_COLLISION_OBJECT), m_userObjectPointer(0), m_userIndex2(-1), @@ -115,18 +114,10 @@ const char* btCollisionObject::serialize(void* dataBuffer, btSerializer* seriali dataOut->m_ccdSweptSphereRadius = m_ccdSweptSphereRadius; dataOut->m_ccdMotionThreshold = m_ccdMotionThreshold; dataOut->m_checkCollideWith = m_checkCollideWith; - if (m_broadphaseHandle) - { - dataOut->m_collisionFilterGroup = m_broadphaseHandle->m_collisionFilterGroup; - dataOut->m_collisionFilterMask = m_broadphaseHandle->m_collisionFilterMask; - dataOut->m_uniqueId = m_broadphaseHandle->m_uniqueId; - } - else - { - dataOut->m_collisionFilterGroup = 0; - dataOut->m_collisionFilterMask = 0; - dataOut->m_uniqueId = -1; - } + + // Fill padding with zeros to appease msan. + memset(dataOut->m_padding, 0, sizeof(dataOut->m_padding)); + return btCollisionObjectDataName; } diff --git a/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionObject.h b/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionObject.h index 135f8a033c37..fec831bffcd2 100644 --- a/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionObject.h +++ b/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionObject.h @@ -621,6 +621,7 @@ struct btCollisionObjectDoubleData double m_hitFraction; double m_ccdSweptSphereRadius; double m_ccdMotionThreshold; + int m_hasAnisotropicFriction; int m_collisionFlags; int m_islandTag1; @@ -628,9 +629,8 @@ struct btCollisionObjectDoubleData int m_activationState1; int m_internalType; int m_checkCollideWith; - int m_collisionFilterGroup; - int m_collisionFilterMask; - int m_uniqueId;//m_uniqueId is introduced for paircache. could get rid of this, by calculating the address offset etc. + + char m_padding[4]; }; ///do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64 @@ -650,12 +650,13 @@ struct btCollisionObjectFloatData float m_deactivationTime; float m_friction; float m_rollingFriction; - float m_contactDamping; + float m_contactDamping; float m_contactStiffness; float m_restitution; float m_hitFraction; float m_ccdSweptSphereRadius; float m_ccdMotionThreshold; + int m_hasAnisotropicFriction; int m_collisionFlags; int m_islandTag1; @@ -663,9 +664,7 @@ struct btCollisionObjectFloatData int m_activationState1; int m_internalType; int m_checkCollideWith; - int m_collisionFilterGroup; - int m_collisionFilterMask; - int m_uniqueId; + char m_padding[4]; }; diff --git a/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp b/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp index 3de8d6995ed0..c893b60d39a8 100644 --- a/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp +++ b/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp @@ -21,7 +21,6 @@ subject to the following restrictions: #include "BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.h" #include "BulletCollision/CollisionShapes/btSphereShape.h" //for raycasting #include "BulletCollision/CollisionShapes/btBvhTriangleMeshShape.h" //for raycasting -#include "BulletCollision/CollisionShapes/btScaledBvhTriangleMeshShape.h" //for raycasting #include "BulletCollision/NarrowPhaseCollision/btRaycastCallback.h" #include "BulletCollision/CollisionShapes/btCompoundShape.h" #include "BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.h" @@ -408,22 +407,6 @@ void btCollisionWorld::rayTestSingleInternal(const btTransform& rayFromTrans,con rcb.m_hitFraction = resultCallback.m_closestHitFraction; triangleMesh->performRaycast(&rcb,rayFromLocal,rayToLocal); } - else if (collisionShape->getShapeType() == SCALED_TRIANGLE_MESH_SHAPE_PROXYTYPE) - { - ///optimized version for btScaledBvhTriangleMeshShape - btScaledBvhTriangleMeshShape* scaledTriangleMesh = (btScaledBvhTriangleMeshShape*)collisionShape; - btBvhTriangleMeshShape* triangleMesh = (btBvhTriangleMeshShape*)scaledTriangleMesh->getChildShape(); - - //scale the ray positions - btVector3 scale = scaledTriangleMesh->getLocalScaling(); - btVector3 rayFromLocalScaled = rayFromLocal / scale; - btVector3 rayToLocalScaled = rayToLocal / scale; - - //perform raycast in the underlying btBvhTriangleMeshShape - BridgeTriangleRaycastCallback rcb(rayFromLocalScaled, rayToLocalScaled, &resultCallback, collisionObjectWrap->getCollisionObject(), triangleMesh, colObjWorldTransform); - rcb.m_hitFraction = resultCallback.m_closestHitFraction; - triangleMesh->performRaycast(&rcb, rayFromLocalScaled, rayToLocalScaled); - } else { //generic (slower) case @@ -1646,7 +1629,7 @@ void btCollisionWorld::serializeCollisionObjects(btSerializer* serializer) for (i=0;igetInternalType() == btCollisionObject::CO_COLLISION_OBJECT) + if ((colObj->getInternalType() == btCollisionObject::CO_COLLISION_OBJECT) || (colObj->getInternalType() == btCollisionObject::CO_FEATHERSTONE_LINK)) { colObj->serializeSingleObject(serializer); } @@ -1654,36 +1637,12 @@ void btCollisionWorld::serializeCollisionObjects(btSerializer* serializer) } - -void btCollisionWorld::serializeContactManifolds(btSerializer* serializer) -{ - if (serializer->getSerializationFlags() & BT_SERIALIZE_CONTACT_MANIFOLDS) - { - int numManifolds = getDispatcher()->getNumManifolds(); - for (int i = 0; i < numManifolds; i++) - { - const btPersistentManifold* manifold = getDispatcher()->getInternalManifoldPointer()[i]; - //don't serialize empty manifolds, they just take space - //(may have to do it anyway if it destroys determinism) - if (manifold->getNumContacts() == 0) - continue; - - btChunk* chunk = serializer->allocate(manifold->calculateSerializeBufferSize(), 1); - const char* structType = manifold->serialize(manifold, chunk->m_oldPtr, serializer); - serializer->finalizeChunk(chunk, structType, BT_CONTACTMANIFOLD_CODE, (void*)manifold); - } - } -} - - void btCollisionWorld::serialize(btSerializer* serializer) { serializer->startSerialization(); serializeCollisionObjects(serializer); - - serializeContactManifolds(serializer); serializer->finishSerialization(); } diff --git a/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionWorld.h b/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionWorld.h index 886476e8ad0f..4a3bf0f7e1ea 100644 --- a/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionWorld.h +++ b/extern/bullet/src/BulletCollision/CollisionDispatch/btCollisionWorld.h @@ -15,7 +15,7 @@ subject to the following restrictions: /** - * @mainpage Bullet Documentation + * @page Bullet Documentation * * @section intro_sec Introduction * Bullet is a Collision Detection and Rigid Body Dynamics Library. The Library is Open Source and free for commercial use, under the ZLib license ( http://opensource.org/licenses/zlib-license.php ). @@ -107,9 +107,6 @@ class btCollisionWorld void serializeCollisionObjects(btSerializer* serializer); - void serializeContactManifolds(btSerializer* serializer); - - public: //this constructor doesn't own the dispatcher and paircache/broadphase diff --git a/extern/bullet/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.cpp b/extern/bullet/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.cpp index 91b7809c17b2..7f4dea1c6ddb 100644 --- a/extern/bullet/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.cpp +++ b/extern/bullet/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.cpp @@ -156,12 +156,10 @@ struct btCompoundLeafCallback : btDbvt::ICollide btCollisionObjectWrapper compoundWrap(this->m_compoundColObjWrap,childShape,m_compoundColObjWrap->getCollisionObject(),newChildWorldTrans,-1,index); btCollisionAlgorithm* algo = 0; - bool allocatedAlgorithm = false; if (m_resultOut->m_closestPointDistanceThreshold > 0) { algo = m_dispatcher->findAlgorithm(&compoundWrap, m_otherObjWrap, 0, BT_CLOSEST_POINT_ALGORITHMS); - allocatedAlgorithm = true; } else { @@ -206,11 +204,7 @@ struct btCompoundLeafCallback : btDbvt::ICollide { m_resultOut->setBody1Wrap(tmpWrap); } - if(allocatedAlgorithm) - { - algo->~btCollisionAlgorithm(); - m_dispatcher->freeCollisionAlgorithm(algo); - } + } } void Process(const btDbvtNode* leaf) @@ -259,9 +253,9 @@ void btCompoundCollisionAlgorithm::processCollision (const btCollisionObjectWrap m_compoundShapeRevision = compoundShape->getUpdateRevision(); } - if (m_childCollisionAlgorithms.size()==0) - return; - + if (m_childCollisionAlgorithms.size()==0) + return; + const btDbvt* tree = compoundShape->getDynamicAabbTree(); //use a dynamic aabb tree to cull potential child-overlaps btCompoundLeafCallback callback(colObjWrap,otherObjWrap,m_dispatcher,dispatchInfo,resultOut,&m_childCollisionAlgorithms[0],m_sharedManifold); diff --git a/extern/bullet/src/BulletCollision/CollisionDispatch/btCompoundCompoundCollisionAlgorithm.cpp b/extern/bullet/src/BulletCollision/CollisionDispatch/btCompoundCompoundCollisionAlgorithm.cpp index 20b542f67069..d4a1aa78e4ee 100644 --- a/extern/bullet/src/BulletCollision/CollisionDispatch/btCompoundCompoundCollisionAlgorithm.cpp +++ b/extern/bullet/src/BulletCollision/CollisionDispatch/btCompoundCompoundCollisionAlgorithm.cpp @@ -181,12 +181,11 @@ struct btCompoundCompoundLeafCallback : btDbvt::ICollide btSimplePair* pair = m_childCollisionAlgorithmCache->findPair(childIndex0,childIndex1); - bool removePair = false; + btCollisionAlgorithm* colAlgo = 0; if (m_resultOut->m_closestPointDistanceThreshold > 0) { colAlgo = m_dispatcher->findAlgorithm(&compoundWrap0, &compoundWrap1, 0, BT_CLOSEST_POINT_ALGORITHMS); - removePair = true; } else { @@ -224,11 +223,7 @@ struct btCompoundCompoundLeafCallback : btDbvt::ICollide m_resultOut->setBody0Wrap(tmpWrap0); m_resultOut->setBody1Wrap(tmpWrap1); - if (removePair) - { - colAlgo->~btCollisionAlgorithm(); - m_dispatcher->freeCollisionAlgorithm(colAlgo); - } + } } @@ -401,24 +396,32 @@ void btCompoundCompoundCollisionAlgorithm::processCollision (const btCollisionOb btCollisionAlgorithm* algo = (btCollisionAlgorithm*)pairs[i].m_userPointer; { + btTransform orgTrans0; const btCollisionShape* childShape0 = 0; btTransform newChildWorldTrans0; + btTransform orgInterpolationTrans0; childShape0 = compoundShape0->getChildShape(pairs[i].m_indexA); + orgTrans0 = col0ObjWrap->getWorldTransform(); + orgInterpolationTrans0 = col0ObjWrap->getWorldTransform(); const btTransform& childTrans0 = compoundShape0->getChildTransform(pairs[i].m_indexA); - newChildWorldTrans0 = col0ObjWrap->getWorldTransform()*childTrans0 ; + newChildWorldTrans0 = orgTrans0*childTrans0 ; childShape0->getAabb(newChildWorldTrans0,aabbMin0,aabbMax0); } btVector3 thresholdVec(resultOut->m_closestPointDistanceThreshold, resultOut->m_closestPointDistanceThreshold, resultOut->m_closestPointDistanceThreshold); aabbMin0 -= thresholdVec; aabbMax0 += thresholdVec; { + btTransform orgInterpolationTrans1; const btCollisionShape* childShape1 = 0; + btTransform orgTrans1; btTransform newChildWorldTrans1; childShape1 = compoundShape1->getChildShape(pairs[i].m_indexB); + orgTrans1 = col1ObjWrap->getWorldTransform(); + orgInterpolationTrans1 = col1ObjWrap->getWorldTransform(); const btTransform& childTrans1 = compoundShape1->getChildTransform(pairs[i].m_indexB); - newChildWorldTrans1 = col1ObjWrap->getWorldTransform()*childTrans1 ; + newChildWorldTrans1 = orgTrans1*childTrans1 ; childShape1->getAabb(newChildWorldTrans1,aabbMin1,aabbMax1); } diff --git a/extern/bullet/src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.cpp b/extern/bullet/src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.cpp index d8cbe9614295..39ff7934d988 100644 --- a/extern/bullet/src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.cpp +++ b/extern/bullet/src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.cpp @@ -27,7 +27,6 @@ subject to the following restrictions: #include "LinearMath/btIDebugDraw.h" #include "BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.h" #include "BulletCollision/CollisionDispatch/btCollisionObjectWrapper.h" -#include "BulletCollision/CollisionShapes/btSdfCollisionShape.h" btConvexConcaveCollisionAlgorithm::btConvexConcaveCollisionAlgorithm( const btCollisionAlgorithmConstructionInfo& ci, const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,bool isSwapped) : btActivatingCollisionAlgorithm(ci,body0Wrap,body1Wrap), @@ -153,7 +152,7 @@ partId, int triangleIndex) { m_resultOut->setBody1Wrap(tmpWrap); } - + colAlgo->~btCollisionAlgorithm(); @@ -164,7 +163,7 @@ partId, int triangleIndex) -void btConvexTriangleCallback::setTimeStepAndCounters(btScalar collisionMarginTriangle, const btDispatcherInfo& dispatchInfo, const btCollisionObjectWrapper* convexBodyWrap, const btCollisionObjectWrapper* triBodyWrap, btManifoldResult* resultOut) +void btConvexTriangleCallback::setTimeStepAndCounters(btScalar collisionMarginTriangle,const btDispatcherInfo& dispatchInfo,const btCollisionObjectWrapper* convexBodyWrap, const btCollisionObjectWrapper* triBodyWrap, btManifoldResult* resultOut) { m_convexBodyWrap = convexBodyWrap; m_triBodyWrap = triBodyWrap; @@ -178,14 +177,14 @@ void btConvexTriangleCallback::setTimeStepAndCounters(btScalar collisionMarginTr convexInTriangleSpace = m_triBodyWrap->getWorldTransform().inverse() * m_convexBodyWrap->getWorldTransform(); const btCollisionShape* convexShape = static_cast(m_convexBodyWrap->getCollisionShape()); //CollisionShape* triangleShape = static_cast(triBody->m_collisionShape); - convexShape->getAabb(convexInTriangleSpace, m_aabbMin, m_aabbMax); - btScalar extraMargin = collisionMarginTriangle + resultOut->m_closestPointDistanceThreshold; - - btVector3 extra(extraMargin, extraMargin, extraMargin); + convexShape->getAabb(convexInTriangleSpace,m_aabbMin,m_aabbMax); + btScalar extraMargin = collisionMarginTriangle+ resultOut->m_closestPointDistanceThreshold; + + btVector3 extra(extraMargin,extraMargin,extraMargin); m_aabbMax += extra; m_aabbMin -= extra; - + } void btConvexConcaveCollisionAlgorithm::clearCache() @@ -194,99 +193,35 @@ void btConvexConcaveCollisionAlgorithm::clearCache() } -void btConvexConcaveCollisionAlgorithm::processCollision (const btCollisionObjectWrapper* body0Wrap, const btCollisionObjectWrapper* body1Wrap, const btDispatcherInfo& dispatchInfo, btManifoldResult* resultOut) +void btConvexConcaveCollisionAlgorithm::processCollision (const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,const btDispatcherInfo& dispatchInfo,btManifoldResult* resultOut) { BT_PROFILE("btConvexConcaveCollisionAlgorithm::processCollision"); - + const btCollisionObjectWrapper* convexBodyWrap = m_isSwapped ? body1Wrap : body0Wrap; const btCollisionObjectWrapper* triBodyWrap = m_isSwapped ? body0Wrap : body1Wrap; if (triBodyWrap->getCollisionShape()->isConcave()) { - if (triBodyWrap->getCollisionShape()->getShapeType() == SDF_SHAPE_PROXYTYPE) - { - btSdfCollisionShape* sdfShape = (btSdfCollisionShape*)triBodyWrap->getCollisionShape(); - if (convexBodyWrap->getCollisionShape()->isConvex()) - { - btConvexShape* convex = (btConvexShape*)convexBodyWrap->getCollisionShape(); - btAlignedObjectArray queryVertices; - - if (convex->isPolyhedral()) - { - btPolyhedralConvexShape* poly = (btPolyhedralConvexShape*)convex; - for (int v = 0; v < poly->getNumVertices(); v++) - { - btVector3 vtx; - poly->getVertex(v, vtx); - queryVertices.push_back(vtx); - } - } - btScalar maxDist = SIMD_EPSILON; - - if (convex->getShapeType() == SPHERE_SHAPE_PROXYTYPE) - { - queryVertices.push_back(btVector3(0, 0, 0)); - btSphereShape* sphere = (btSphereShape*)convex; - maxDist = sphere->getRadius() + SIMD_EPSILON; - - } - if (queryVertices.size()) - { - resultOut->setPersistentManifold(m_btConvexTriangleCallback.m_manifoldPtr); - //m_btConvexTriangleCallback.m_manifoldPtr->clearManifold(); - - btPolyhedralConvexShape* poly = (btPolyhedralConvexShape*)convex; - for (int v = 0; v < queryVertices.size(); v++) - { - const btVector3& vtx = queryVertices[v]; - btVector3 vtxWorldSpace = convexBodyWrap->getWorldTransform()*vtx; - btVector3 vtxInSdf = triBodyWrap->getWorldTransform().invXform(vtxWorldSpace); - - btVector3 normalLocal; - btScalar dist; - if (sdfShape->queryPoint(vtxInSdf, dist, normalLocal)) - { - if (dist <= maxDist) - { - normalLocal.safeNormalize(); - btVector3 normal = triBodyWrap->getWorldTransform().getBasis()*normalLocal; - - if (convex->getShapeType() == SPHERE_SHAPE_PROXYTYPE) - { - btSphereShape* sphere = (btSphereShape*)convex; - dist -= sphere->getRadius(); - vtxWorldSpace -= sphere->getRadius()*normal; - - } - resultOut->addContactPoint(normal,vtxWorldSpace-normal*dist, dist); - } - } - } - resultOut->refreshContactPoints(); - } - } - } else - { - const btConcaveShape* concaveShape = static_cast( triBodyWrap->getCollisionShape()); - if (convexBodyWrap->getCollisionShape()->isConvex()) - { - btScalar collisionMarginTriangle = concaveShape->getMargin(); + const btConcaveShape* concaveShape = static_cast( triBodyWrap->getCollisionShape()); + + if (convexBodyWrap->getCollisionShape()->isConvex()) + { + btScalar collisionMarginTriangle = concaveShape->getMargin(); - resultOut->setPersistentManifold(m_btConvexTriangleCallback.m_manifoldPtr); - m_btConvexTriangleCallback.setTimeStepAndCounters(collisionMarginTriangle,dispatchInfo,convexBodyWrap,triBodyWrap,resultOut); + resultOut->setPersistentManifold(m_btConvexTriangleCallback.m_manifoldPtr); + m_btConvexTriangleCallback.setTimeStepAndCounters(collisionMarginTriangle,dispatchInfo,convexBodyWrap,triBodyWrap,resultOut); - m_btConvexTriangleCallback.m_manifoldPtr->setBodies(convexBodyWrap->getCollisionObject(),triBodyWrap->getCollisionObject()); + m_btConvexTriangleCallback.m_manifoldPtr->setBodies(convexBodyWrap->getCollisionObject(),triBodyWrap->getCollisionObject()); - concaveShape->processAllTriangles( &m_btConvexTriangleCallback,m_btConvexTriangleCallback.getAabbMin(),m_btConvexTriangleCallback.getAabbMax()); + concaveShape->processAllTriangles( &m_btConvexTriangleCallback,m_btConvexTriangleCallback.getAabbMin(),m_btConvexTriangleCallback.getAabbMax()); - resultOut->refreshContactPoints(); + resultOut->refreshContactPoints(); - m_btConvexTriangleCallback.clearWrapperData(); + m_btConvexTriangleCallback.clearWrapperData(); - } } } diff --git a/extern/bullet/src/BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.cpp b/extern/bullet/src/BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.cpp index 3e8bc6e426e7..b54bd48932ed 100644 --- a/extern/bullet/src/BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.cpp +++ b/extern/bullet/src/BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.cpp @@ -28,7 +28,6 @@ subject to the following restrictions: #include "BulletCollision/CollisionShapes/btConvexShape.h" #include "BulletCollision/CollisionShapes/btCapsuleShape.h" #include "BulletCollision/CollisionShapes/btTriangleShape.h" -#include "BulletCollision/CollisionShapes/btConvexPolyhedron.h" @@ -260,7 +259,7 @@ struct btPerturbedContactResult : public btManifoldResult btVector3 endPtOrg = pointInWorld + normalOnBInWorld*orgDepth; endPt = (m_unPerturbedTransform*m_transformA.inverse())(endPtOrg); newDepth = (endPt - pointInWorld).dot(normalOnBInWorld); - startPt = endPt - normalOnBInWorld*newDepth; + startPt = endPt+normalOnBInWorld*newDepth; } else { endPt = pointInWorld + normalOnBInWorld*orgDepth; @@ -443,26 +442,10 @@ void btConvexConvexAlgorithm ::processCollision (const btCollisionObjectWrapper* struct btDummyResult : public btDiscreteCollisionDetectorInterface::Result { - btVector3 m_normalOnBInWorld; - btVector3 m_pointInWorld; - btScalar m_depth; - bool m_hasContact; - - - btDummyResult() - : m_hasContact(false) - { - } - - virtual void setShapeIdentifiersA(int partId0,int index0){} virtual void setShapeIdentifiersB(int partId1,int index1){} virtual void addContactPoint(const btVector3& normalOnBInWorld,const btVector3& pointInWorld,btScalar depth) { - m_hasContact = true; - m_normalOnBInWorld = normalOnBInWorld; - m_pointInWorld = pointInWorld; - m_depth = depth; } }; @@ -577,18 +560,15 @@ void btConvexConvexAlgorithm ::processCollision (const btCollisionObjectWrapper* } else { - - //we can also deal with convex versus triangle (without connectivity data) - if (dispatchInfo.m_enableSatConvex && polyhedronA->getConvexPolyhedron() && polyhedronB->getShapeType()==TRIANGLE_SHAPE_PROXYTYPE) + if (polyhedronA->getConvexPolyhedron() && polyhedronB->getShapeType()==TRIANGLE_SHAPE_PROXYTYPE) { - - btVertexArray worldSpaceVertices; + btVertexArray vertices; btTriangleShape* tri = (btTriangleShape*)polyhedronB; - worldSpaceVertices.push_back( body1Wrap->getWorldTransform()*tri->m_vertices1[0]); - worldSpaceVertices.push_back( body1Wrap->getWorldTransform()*tri->m_vertices1[1]); - worldSpaceVertices.push_back( body1Wrap->getWorldTransform()*tri->m_vertices1[2]); + vertices.push_back( body1Wrap->getWorldTransform()*tri->m_vertices1[0]); + vertices.push_back( body1Wrap->getWorldTransform()*tri->m_vertices1[1]); + vertices.push_back( body1Wrap->getWorldTransform()*tri->m_vertices1[2]); //tri->initializePolyhedralFeatures(); @@ -599,99 +579,17 @@ void btConvexConvexAlgorithm ::processCollision (const btCollisionObjectWrapper* btScalar maxDist = threshold; bool foundSepAxis = false; - bool useSatSepNormal = true; - - if (useSatSepNormal) + if (0) { -#if 0 - if (0) - { - //initializePolyhedralFeatures performs a convex hull computation, not needed for a single triangle - polyhedronB->initializePolyhedralFeatures(); - } else -#endif - { - - btVector3 uniqueEdges[3] = {tri->m_vertices1[1]-tri->m_vertices1[0], - tri->m_vertices1[2]-tri->m_vertices1[1], - tri->m_vertices1[0]-tri->m_vertices1[2]}; - - uniqueEdges[0].normalize(); - uniqueEdges[1].normalize(); - uniqueEdges[2].normalize(); - - btConvexPolyhedron polyhedron; - polyhedron.m_vertices.push_back(tri->m_vertices1[2]); - polyhedron.m_vertices.push_back(tri->m_vertices1[0]); - polyhedron.m_vertices.push_back(tri->m_vertices1[1]); - - - { - btFace combinedFaceA; - combinedFaceA.m_indices.push_back(0); - combinedFaceA.m_indices.push_back(1); - combinedFaceA.m_indices.push_back(2); - btVector3 faceNormal = uniqueEdges[0].cross(uniqueEdges[1]); - faceNormal.normalize(); - btScalar planeEq=1e30f; - for (int v=0;vm_vertices1[combinedFaceA.m_indices[v]].dot(faceNormal); - if (planeEq>eq) - { - planeEq=eq; - } - } - combinedFaceA.m_plane[0] = faceNormal[0]; - combinedFaceA.m_plane[1] = faceNormal[1]; - combinedFaceA.m_plane[2] = faceNormal[2]; - combinedFaceA.m_plane[3] = -planeEq; - polyhedron.m_faces.push_back(combinedFaceA); - } - { - btFace combinedFaceB; - combinedFaceB.m_indices.push_back(0); - combinedFaceB.m_indices.push_back(2); - combinedFaceB.m_indices.push_back(1); - btVector3 faceNormal = -uniqueEdges[0].cross(uniqueEdges[1]); - faceNormal.normalize(); - btScalar planeEq=1e30f; - for (int v=0;vm_vertices1[combinedFaceB.m_indices[v]].dot(faceNormal); - if (planeEq>eq) - { - planeEq=eq; - } - } - - combinedFaceB.m_plane[0] = faceNormal[0]; - combinedFaceB.m_plane[1] = faceNormal[1]; - combinedFaceB.m_plane[2] = faceNormal[2]; - combinedFaceB.m_plane[3] = -planeEq; - polyhedron.m_faces.push_back(combinedFaceB); - } - - - polyhedron.m_uniqueEdges.push_back(uniqueEdges[0]); - polyhedron.m_uniqueEdges.push_back(uniqueEdges[1]); - polyhedron.m_uniqueEdges.push_back(uniqueEdges[2]); - polyhedron.initialize2(); - - polyhedronB->setPolyhedralFeatures(polyhedron); - } - - - + polyhedronB->initializePolyhedralFeatures(); foundSepAxis = btPolyhedralContactClipping::findSeparatingAxis( - *polyhedronA->getConvexPolyhedron(), *polyhedronB->getConvexPolyhedron(), - body0Wrap->getWorldTransform(), - body1Wrap->getWorldTransform(), - sepNormalWorldSpace,*resultOut); + *polyhedronA->getConvexPolyhedron(), *polyhedronB->getConvexPolyhedron(), + body0Wrap->getWorldTransform(), + body1Wrap->getWorldTransform(), + sepNormalWorldSpace,*resultOut); // printf("sepNormalWorldSpace=%f,%f,%f\n",sepNormalWorldSpace.getX(),sepNormalWorldSpace.getY(),sepNormalWorldSpace.getZ()); - } - else + } else { #ifdef ZERO_MARGIN gjkPairDetector.setIgnoreMargin(true); @@ -700,24 +598,6 @@ void btConvexConvexAlgorithm ::processCollision (const btCollisionObjectWrapper* gjkPairDetector.getClosestPoints(input,dummy,dispatchInfo.m_debugDraw); #endif//ZERO_MARGIN - if (dummy.m_hasContact && dummy.m_depth<0) - { - - if (foundSepAxis) - { - if (dummy.m_normalOnBInWorld.dot(sepNormalWorldSpace)<0.99) - { - printf("?\n"); - } - } else - { - printf("!\n"); - } - sepNormalWorldSpace.setValue(0,0,1);// = dummy.m_normalOnBInWorld; - //minDist = dummy.m_depth; - foundSepAxis = true; - } -#if 0 btScalar l2 = gjkPairDetector.getCachedSeparatingAxis().length2(); if (l2>SIMD_EPSILON) { @@ -727,7 +607,6 @@ void btConvexConvexAlgorithm ::processCollision (const btCollisionObjectWrapper* minDist = gjkPairDetector.getCachedSeparatingDistance()-min0->getMargin()-min1->getMargin(); foundSepAxis = true; } -#endif } @@ -735,7 +614,7 @@ void btConvexConvexAlgorithm ::processCollision (const btCollisionObjectWrapper* { worldVertsB2.resize(0); btPolyhedralContactClipping::clipFaceAgainstHull(sepNormalWorldSpace, *polyhedronA->getConvexPolyhedron(), - body0Wrap->getWorldTransform(), worldSpaceVertices, worldVertsB2,minDist-threshold, maxDist, *resultOut); + body0Wrap->getWorldTransform(), vertices, worldVertsB2,minDist-threshold, maxDist, *resultOut); } @@ -746,7 +625,6 @@ void btConvexConvexAlgorithm ::processCollision (const btCollisionObjectWrapper* return; } - } diff --git a/extern/bullet/src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.cpp b/extern/bullet/src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.cpp index 8271981b29d6..8c8a7c3c1e3b 100644 --- a/extern/bullet/src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.cpp +++ b/extern/bullet/src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.cpp @@ -20,12 +20,11 @@ subject to the following restrictions: #include -#ifdef BT_DEBUG_COLLISION_PAIRS int gOverlappingSimplePairs = 0; int gRemoveSimplePairs =0; int gAddedSimplePairs =0; int gFindSimplePairs =0; -#endif //BT_DEBUG_COLLISION_PAIRS + @@ -62,9 +61,7 @@ void btHashedSimplePairCache::removeAllPairs() btSimplePair* btHashedSimplePairCache::findPair(int indexA, int indexB) { -#ifdef BT_DEBUG_COLLISION_PAIRS gFindSimplePairs++; -#endif /*if (indexA > indexB) @@ -175,9 +172,7 @@ btSimplePair* btHashedSimplePairCache::internalAddPair(int indexA, int indexB) void* btHashedSimplePairCache::removeOverlappingPair(int indexA, int indexB) { -#ifdef BT_DEBUG_COLLISION_PAIRS gRemoveSimplePairs++; -#endif /*if (indexA > indexB) diff --git a/extern/bullet/src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.h b/extern/bullet/src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.h index 318981cda1c8..2aaf6201f30d 100644 --- a/extern/bullet/src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.h +++ b/extern/bullet/src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.h @@ -43,12 +43,12 @@ struct btSimplePair typedef btAlignedObjectArray btSimplePairArray; -#ifdef BT_DEBUG_COLLISION_PAIRS + extern int gOverlappingSimplePairs; extern int gRemoveSimplePairs; extern int gAddedSimplePairs; extern int gFindSimplePairs; -#endif //BT_DEBUG_COLLISION_PAIRS + @@ -75,9 +75,7 @@ class btHashedSimplePairCache // no new pair is created and the old one is returned. virtual btSimplePair* addOverlappingPair(int indexA,int indexB) { -#ifdef BT_DEBUG_COLLISION_PAIRS gAddedSimplePairs++; -#endif return internalAddPair(indexA,indexB); } diff --git a/extern/bullet/src/BulletCollision/CollisionDispatch/btManifoldResult.cpp b/extern/bullet/src/BulletCollision/CollisionDispatch/btManifoldResult.cpp index 23c73c88254c..aa3d159f889b 100644 --- a/extern/bullet/src/BulletCollision/CollisionDispatch/btManifoldResult.cpp +++ b/extern/bullet/src/BulletCollision/CollisionDispatch/btManifoldResult.cpp @@ -22,12 +22,7 @@ subject to the following restrictions: ///This is to allow MaterialCombiner/Custom Friction/Restitution values ContactAddedCallback gContactAddedCallback=0; -CalculateCombinedCallback gCalculateCombinedRestitutionCallback = &btManifoldResult::calculateCombinedRestitution; -CalculateCombinedCallback gCalculateCombinedFrictionCallback = &btManifoldResult::calculateCombinedFriction; -CalculateCombinedCallback gCalculateCombinedRollingFrictionCallback = &btManifoldResult::calculateCombinedRollingFriction; -CalculateCombinedCallback gCalculateCombinedSpinningFrictionCallback = &btManifoldResult::calculateCombinedSpinningFriction; -CalculateCombinedCallback gCalculateCombinedContactDampingCallback = &btManifoldResult::calculateCombinedContactDamping; -CalculateCombinedCallback gCalculateCombinedContactStiffnessCallback = &btManifoldResult::calculateCombinedContactStiffness; + btScalar btManifoldResult::calculateCombinedRollingFriction(const btCollisionObject* body0,const btCollisionObject* body1) { @@ -139,16 +134,16 @@ void btManifoldResult::addContactPoint(const btVector3& normalOnBInWorld,const b int insertIndex = m_manifoldPtr->getCacheEntry(newPt); - newPt.m_combinedFriction = gCalculateCombinedFrictionCallback(m_body0Wrap->getCollisionObject(),m_body1Wrap->getCollisionObject()); - newPt.m_combinedRestitution = gCalculateCombinedRestitutionCallback(m_body0Wrap->getCollisionObject(),m_body1Wrap->getCollisionObject()); - newPt.m_combinedRollingFriction = gCalculateCombinedRollingFrictionCallback(m_body0Wrap->getCollisionObject(),m_body1Wrap->getCollisionObject()); - newPt.m_combinedSpinningFriction = gCalculateCombinedSpinningFrictionCallback(m_body0Wrap->getCollisionObject(),m_body1Wrap->getCollisionObject()); + newPt.m_combinedFriction = calculateCombinedFriction(m_body0Wrap->getCollisionObject(),m_body1Wrap->getCollisionObject()); + newPt.m_combinedRestitution = calculateCombinedRestitution(m_body0Wrap->getCollisionObject(),m_body1Wrap->getCollisionObject()); + newPt.m_combinedRollingFriction = calculateCombinedRollingFriction(m_body0Wrap->getCollisionObject(),m_body1Wrap->getCollisionObject()); + newPt.m_combinedSpinningFriction = calculateCombinedSpinningFriction(m_body0Wrap->getCollisionObject(),m_body1Wrap->getCollisionObject()); if ( (m_body0Wrap->getCollisionObject()->getCollisionFlags()& btCollisionObject::CF_HAS_CONTACT_STIFFNESS_DAMPING) || (m_body1Wrap->getCollisionObject()->getCollisionFlags()& btCollisionObject::CF_HAS_CONTACT_STIFFNESS_DAMPING)) { - newPt.m_combinedContactDamping1 = gCalculateCombinedContactDampingCallback(m_body0Wrap->getCollisionObject(),m_body1Wrap->getCollisionObject()); - newPt.m_combinedContactStiffness1 = gCalculateCombinedContactStiffnessCallback(m_body0Wrap->getCollisionObject(),m_body1Wrap->getCollisionObject()); + newPt.m_combinedContactDamping1 = calculateCombinedContactDamping(m_body0Wrap->getCollisionObject(),m_body1Wrap->getCollisionObject()); + newPt.m_combinedContactStiffness1 = calculateCombinedContactStiffness(m_body0Wrap->getCollisionObject(),m_body1Wrap->getCollisionObject()); newPt.m_contactPointFlags |= BT_CONTACT_FLAG_CONTACT_STIFFNESS_DAMPING; } diff --git a/extern/bullet/src/BulletCollision/CollisionDispatch/btManifoldResult.h b/extern/bullet/src/BulletCollision/CollisionDispatch/btManifoldResult.h index 12cdafd1b6ae..86bbc3f7295d 100644 --- a/extern/bullet/src/BulletCollision/CollisionDispatch/btManifoldResult.h +++ b/extern/bullet/src/BulletCollision/CollisionDispatch/btManifoldResult.h @@ -34,15 +34,6 @@ extern ContactAddedCallback gContactAddedCallback; //#define DEBUG_PART_INDEX 1 -/// These callbacks are used to customize the algorith that combine restitution, friction, damping, Stiffness -typedef btScalar (*CalculateCombinedCallback)(const btCollisionObject* body0,const btCollisionObject* body1); - -extern CalculateCombinedCallback gCalculateCombinedRestitutionCallback; -extern CalculateCombinedCallback gCalculateCombinedFrictionCallback; -extern CalculateCombinedCallback gCalculateCombinedRollingFrictionCallback; -extern CalculateCombinedCallback gCalculateCombinedSpinningFrictionCallback; -extern CalculateCombinedCallback gCalculateCombinedContactDampingCallback; -extern CalculateCombinedCallback gCalculateCombinedContactStiffnessCallback; ///btManifoldResult is a helper class to manage contact results. class btManifoldResult : public btDiscreteCollisionDetectorInterface::Result diff --git a/extern/bullet/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.cpp b/extern/bullet/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.cpp index 91c76a8dac42..13447822571d 100644 --- a/extern/bullet/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.cpp +++ b/extern/bullet/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.cpp @@ -199,22 +199,6 @@ class btPersistentManifoldSortPredicate } }; -class btPersistentManifoldSortPredicateDeterministic -{ -public: - - SIMD_FORCE_INLINE bool operator() (const btPersistentManifold* lhs, const btPersistentManifold* rhs) const - { - return ( - (getIslandId(lhs) < getIslandId(rhs)) - || ((getIslandId(lhs) == getIslandId(rhs)) && lhs->getBody0()->getBroadphaseHandle()->m_uniqueId < rhs->getBody0()->getBroadphaseHandle()->m_uniqueId) - ||((getIslandId(lhs) == getIslandId(rhs)) && (lhs->getBody0()->getBroadphaseHandle()->m_uniqueId == rhs->getBody0()->getBroadphaseHandle()->m_uniqueId) && - (lhs->getBody1()->getBroadphaseHandle()->m_uniqueId < rhs->getBody1()->getBroadphaseHandle()->m_uniqueId)) - ); - - } -}; - void btSimulationIslandManager::buildIslands(btDispatcher* dispatcher,btCollisionWorld* collisionWorld) { @@ -261,11 +245,13 @@ void btSimulationIslandManager::buildIslands(btDispatcher* dispatcher,btCollisio btAssert((colObj0->getIslandTag() == islandId) || (colObj0->getIslandTag() == -1)); if (colObj0->getIslandTag() == islandId) { - if (colObj0->getActivationState()== ACTIVE_TAG || - colObj0->getActivationState()== DISABLE_DEACTIVATION) + if (colObj0->getActivationState()== ACTIVE_TAG) + { + allSleeping = false; + } + if (colObj0->getActivationState()== DISABLE_DEACTIVATION) { allSleeping = false; - break; } } } @@ -332,12 +318,7 @@ void btSimulationIslandManager::buildIslands(btDispatcher* dispatcher,btCollisio for (i=0;igetManifoldByIndexInternal(i); - if (collisionWorld->getDispatchInfo().m_deterministicOverlappingPairs) - { - if (manifold->getNumContacts() == 0) - continue; - } - + const btCollisionObject* colObj0 = static_cast(manifold->getBody0()); const btCollisionObject* colObj1 = static_cast(manifold->getBody1()); @@ -398,16 +379,7 @@ void btSimulationIslandManager::buildAndProcessIslands(btDispatcher* dispatcher, //tried a radix sort, but quicksort/heapsort seems still faster //@todo rewrite island management - //btPersistentManifoldSortPredicateDeterministic sorts contact manifolds based on islandid, - //but also based on object0 unique id and object1 unique id - if (collisionWorld->getDispatchInfo().m_deterministicOverlappingPairs) - { - m_islandmanifold.quickSort(btPersistentManifoldSortPredicateDeterministic()); - } else - { - m_islandmanifold.quickSort(btPersistentManifoldSortPredicate()); - } - + m_islandmanifold.quickSort(btPersistentManifoldSortPredicate()); //m_islandmanifold.heapSort(btPersistentManifoldSortPredicate()); //now process all active islands (sets of manifolds for now) diff --git a/extern/bullet/src/BulletCollision/CollisionShapes/btCapsuleShape.h b/extern/bullet/src/BulletCollision/CollisionShapes/btCapsuleShape.h index 5a3362834a5a..7d64b46abf89 100644 --- a/extern/bullet/src/BulletCollision/CollisionShapes/btCapsuleShape.h +++ b/extern/bullet/src/BulletCollision/CollisionShapes/btCapsuleShape.h @@ -49,7 +49,6 @@ ATTRIBUTE_ALIGNED16(class) btCapsuleShape : public btConvexInternalShape virtual void setMargin(btScalar collisionMargin) { //don't override the margin for capsules, their entire radius == margin - (void)collisionMargin; } virtual void getAabb (const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const diff --git a/extern/bullet/src/BulletCollision/CollisionShapes/btCompoundShape.cpp b/extern/bullet/src/BulletCollision/CollisionShapes/btCompoundShape.cpp index 85572da307db..e8c8c336cd2c 100644 --- a/extern/bullet/src/BulletCollision/CollisionShapes/btCompoundShape.cpp +++ b/extern/bullet/src/BulletCollision/CollisionShapes/btCompoundShape.cpp @@ -213,7 +213,7 @@ void btCompoundShape::calculateLocalInertia(btScalar mass,btVector3& inertia) co -void btCompoundShape::calculatePrincipalAxisTransform(const btScalar* masses, btTransform& principal, btVector3& inertia) const +void btCompoundShape::calculatePrincipalAxisTransform(btScalar* masses, btTransform& principal, btVector3& inertia) const { int n = m_children.size(); diff --git a/extern/bullet/src/BulletCollision/CollisionShapes/btCompoundShape.h b/extern/bullet/src/BulletCollision/CollisionShapes/btCompoundShape.h index 2cbcd1bfca26..4eef8dba3068 100644 --- a/extern/bullet/src/BulletCollision/CollisionShapes/btCompoundShape.h +++ b/extern/bullet/src/BulletCollision/CollisionShapes/btCompoundShape.h @@ -160,7 +160,7 @@ ATTRIBUTE_ALIGNED16(class) btCompoundShape : public btCollisionShape ///"principal" has to be applied inversely to all children transforms in order for the local coordinate system of the compound ///shape to be centered at the center of mass and to coincide with the principal axes. This also necessitates a correction of the world transform ///of the collision object by the principal transform. - void calculatePrincipalAxisTransform(const btScalar* masses, btTransform& principal, btVector3& inertia) const; + void calculatePrincipalAxisTransform(btScalar* masses, btTransform& principal, btVector3& inertia) const; int getUpdateRevision() const { diff --git a/extern/bullet/src/BulletCollision/CollisionShapes/btConvexHullShape.cpp b/extern/bullet/src/BulletCollision/CollisionShapes/btConvexHullShape.cpp index a7a9598406aa..eec2b8d769ea 100644 --- a/extern/bullet/src/BulletCollision/CollisionShapes/btConvexHullShape.cpp +++ b/extern/bullet/src/BulletCollision/CollisionShapes/btConvexHullShape.cpp @@ -13,9 +13,9 @@ subject to the following restrictions: 3. This notice may not be removed or altered from any source distribution. */ -#if defined (_WIN32) || defined (__i386__) -#define BT_USE_SSE_IN_API -#endif +//#if defined (_WIN32) || defined (__i386__) +//#define BT_USE_SSE_IN_API +//#endif #include "btConvexHullShape.h" #include "BulletCollision/CollisionShapes/btCollisionMargin.h" diff --git a/extern/bullet/src/BulletCollision/CollisionShapes/btConvexPolyhedron.cpp b/extern/bullet/src/BulletCollision/CollisionShapes/btConvexPolyhedron.cpp index 0fea00df5c16..4f45319a83a9 100644 --- a/extern/bullet/src/BulletCollision/CollisionShapes/btConvexPolyhedron.cpp +++ b/extern/bullet/src/BulletCollision/CollisionShapes/btConvexPolyhedron.cpp @@ -104,9 +104,9 @@ void btConvexPolyhedron::initialize() btHashMap edges; + btScalar TotalArea = 0.0f; - - + m_localCenter.setValue(0, 0, 0); for(int i=0;i= 0); - if (ptIndex<0) - { - ptIndex = 0; - } btVector3 supVec = points[ptIndex] * localScaling; return supVec; #endif //__SPU__ diff --git a/extern/bullet/src/BulletCollision/CollisionShapes/btMiniSDF.cpp b/extern/bullet/src/BulletCollision/CollisionShapes/btMiniSDF.cpp deleted file mode 100644 index afe45e1d2d02..000000000000 --- a/extern/bullet/src/BulletCollision/CollisionShapes/btMiniSDF.cpp +++ /dev/null @@ -1,532 +0,0 @@ -#include "btMiniSDF.h" - -// -//Based on code from DiscreGrid, https://github.com/InteractiveComputerGraphics/Discregrid -//example: -//GenerateSDF.exe -r "32 32 32" -d "-1.6 -1.6 -.6 1.6 1.6 .6" concave_box.obj -//The MIT License (MIT) -// -//Copyright (c) 2017 Dan Koschier -// - -#include -#include //memcpy - -struct btSdfDataStream -{ - const char* m_data; - int m_size; - - int m_currentOffset; - - btSdfDataStream(const char* data, int size) - :m_data(data), - m_size(size), - m_currentOffset(0) - { - - } - - template bool read(T& val) - { - int bytes = sizeof(T); - if (m_currentOffset+bytes<=m_size) - { - char* dest = (char*)&val; - memcpy(dest,&m_data[m_currentOffset],bytes); - m_currentOffset+=bytes; - return true; - } - btAssert(0); - return false; - } -}; - - -bool btMiniSDF::load(const char* data, int size) -{ - int fileSize = -1; - - btSdfDataStream ds(data,size); - { - double buf[6]; - ds.read(buf); - m_domain.m_min[0] = buf[0]; - m_domain.m_min[1] = buf[1]; - m_domain.m_min[2] = buf[2]; - m_domain.m_min[3] = 0; - m_domain.m_max[0] = buf[3]; - m_domain.m_max[1] = buf[4]; - m_domain.m_max[2] = buf[5]; - m_domain.m_max[3] = 0; - } - { - unsigned int buf2[3]; - ds.read(buf2); - m_resolution[0] = buf2[0]; - m_resolution[1] = buf2[1]; - m_resolution[2] = buf2[2]; - } - { - double buf[3]; - ds.read(buf); - m_cell_size[0] = buf[0]; - m_cell_size[1] = buf[1]; - m_cell_size[2] = buf[2]; - } - { - double buf[3]; - ds.read(buf); - m_inv_cell_size[0] = buf[0]; - m_inv_cell_size[1] = buf[1]; - m_inv_cell_size[2] = buf[2]; - } - { - unsigned long long int cells; - ds.read(cells); - m_n_cells = cells; - } - { - unsigned long long int fields; - ds.read(fields); - m_n_fields = fields; - } - - - unsigned long long int nodes0; - std::size_t n_nodes0; - ds.read(nodes0); - n_nodes0 = nodes0; - if (n_nodes0 > 1024 * 1024 * 1024) - { - return m_isValid; - } - m_nodes.resize(n_nodes0); - for (unsigned int i=0;i& nodes = m_nodes[i]; - nodes.resize(n_nodes1); - for ( int j=0;j& cells = m_cells[i]; - ds.read(n_cells1); - cells.resize(n_cells1); - for (int j=0;j& cell_maps = m_cell_map[i]; - ds.read(n_cell_maps1); - cell_maps.resize(n_cell_maps1); - for (int j=0;j().eval(); - unsigned int mi[3] = {(unsigned int )tmpmi[0],(unsigned int )tmpmi[1],(unsigned int )tmpmi[2]}; - if (mi[0] >= m_resolution[0]) - mi[0] = m_resolution[0]-1; - if (mi[1] >= m_resolution[1]) - mi[1] = m_resolution[1]-1; - if (mi[2] >= m_resolution[2]) - mi[2] = m_resolution[2]-1; - btMultiIndex mui; - mui.ijk[0] = mi[0]; - mui.ijk[1] = mi[1]; - mui.ijk[2] = mi[2]; - int i = multiToSingleIndex(mui); - unsigned int i_ = m_cell_map[field_id][i]; - if (i_ == UINT_MAX) - return false; - - btAlignedBox3d sd = subdomain(i); - i = i_; - btVector3 d = sd.m_max-sd.m_min;//.diagonal().eval(); - - btVector3 denom = (sd.max() - sd.min()); - btVector3 c0 = btVector3(2.0,2.0,2.0)/denom; - btVector3 c1 = (sd.max() + sd.min())/denom; - btVector3 xi = (c0*x - c1); - - btCell32 const& cell = m_cells[field_id][i]; - if (!gradient) - { - //auto phi = m_coefficients[field_id][i].dot(shape_function_(xi, 0)); - double phi = 0.0; - btShapeMatrix N = shape_function_(xi, 0); - for (unsigned int j = 0u; j < 32u; ++j) - { - unsigned int v = cell.m_cells[j]; - double c = m_nodes[field_id][v]; - if (c == DBL_MAX) - { - return false;; - } - phi += c * N[j]; - } - - dist = phi; - return true; - } - - btShapeGradients dN; - btShapeMatrix N = shape_function_(xi, &dN); - - double phi = 0.0; - gradient->setZero(); - for (unsigned int j = 0u; j < 32u; ++j) - { - unsigned int v = cell.m_cells[j]; - double c = m_nodes[field_id][v]; - if (c == DBL_MAX) - { - gradient->setZero(); - return false; - } - phi += c * N[j]; - (*gradient)[0] += c * dN(j, 0); - (*gradient)[1] += c * dN(j, 1); - (*gradient)[2] += c * dN(j, 2); - } - (*gradient) *= c0; - dist = phi; - return true; -} - diff --git a/extern/bullet/src/BulletCollision/CollisionShapes/btMiniSDF.h b/extern/bullet/src/BulletCollision/CollisionShapes/btMiniSDF.h deleted file mode 100644 index 3de90e4f8ad5..000000000000 --- a/extern/bullet/src/BulletCollision/CollisionShapes/btMiniSDF.h +++ /dev/null @@ -1,134 +0,0 @@ -#ifndef MINISDF_H -#define MINISDF_H - -#include "LinearMath/btVector3.h" -#include "LinearMath/btAabbUtil2.h" -#include "LinearMath/btAlignedObjectArray.h" - - -struct btMultiIndex -{ - unsigned int ijk[3]; -}; - -struct btAlignedBox3d -{ - btVector3 m_min; - btVector3 m_max; - - const btVector3& min() const - { - return m_min; - } - - const btVector3& max() const - { - return m_max; - } - - - bool contains(const btVector3& x) const - { - return TestPointAgainstAabb2(m_min, m_max, x); - } - - btAlignedBox3d(const btVector3& mn, const btVector3& mx) - :m_min(mn), - m_max(mx) - { - } - - btAlignedBox3d() - { - } -}; - -struct btShapeMatrix -{ - double m_vec[32]; - - inline double& operator[](int i) - { - return m_vec[i]; - } - - inline const double& operator[](int i) const - { - return m_vec[i]; - } - -}; - -struct btShapeGradients -{ - btVector3 m_vec[32]; - - void topRowsDivide(int row, double denom) - { - for (int i=0;i > m_nodes; - btAlignedObjectArray > m_cells; - btAlignedObjectArray > m_cell_map; - - btMiniSDF() - :m_isValid(false) - { - } - bool load(const char* data, int size); - bool isValid() const - { - return m_isValid; - } - unsigned int multiToSingleIndex(btMultiIndex const & ijk) const; - - btAlignedBox3d subdomain(btMultiIndex const& ijk) const; - - btMultiIndex singleToMultiIndex(unsigned int l) const; - - btAlignedBox3d subdomain(unsigned int l) const; - - - btShapeMatrix - shape_function_(btVector3 const& xi, btShapeGradients* gradient = 0) const; - - bool interpolate(unsigned int field_id, double& dist, btVector3 const& x, btVector3* gradient) const; -}; - - -#endif //MINISDF_H diff --git a/extern/bullet/src/BulletCollision/CollisionShapes/btMultiSphereShape.cpp b/extern/bullet/src/BulletCollision/CollisionShapes/btMultiSphereShape.cpp index 4195fa313882..d5bf6d60fe3f 100644 --- a/extern/bullet/src/BulletCollision/CollisionShapes/btMultiSphereShape.cpp +++ b/extern/bullet/src/BulletCollision/CollisionShapes/btMultiSphereShape.cpp @@ -13,9 +13,9 @@ subject to the following restrictions: 3. This notice may not be removed or altered from any source distribution. */ -#if defined (_WIN32) || defined (__i386__) -#define BT_USE_SSE_IN_API -#endif +//#if defined (_WIN32) || defined (__i386__) +//#define BT_USE_SSE_IN_API +//#endif #include "btMultiSphereShape.h" #include "BulletCollision/CollisionShapes/btCollisionMargin.h" diff --git a/extern/bullet/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.cpp b/extern/bullet/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.cpp index d51b6760fc1c..9095c592d87d 100644 --- a/extern/bullet/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.cpp +++ b/extern/bullet/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.cpp @@ -12,9 +12,9 @@ subject to the following restrictions: 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 3. This notice may not be removed or altered from any source distribution. */ -#if defined (_WIN32) || defined (__i386__) -#define BT_USE_SSE_IN_API -#endif +//#if defined (_WIN32) || defined (__i386__) +//#define BT_USE_SSE_IN_API +//#endif #include "BulletCollision/CollisionShapes/btPolyhedralConvexShape.h" #include "btConvexPolyhedron.h" @@ -39,17 +39,6 @@ btPolyhedralConvexShape::~btPolyhedralConvexShape() } } -void btPolyhedralConvexShape::setPolyhedralFeatures(btConvexPolyhedron& polyhedron) -{ - if (m_polyhedron) - { - *m_polyhedron = polyhedron; - } else - { - void* mem = btAlignedAlloc(sizeof(btConvexPolyhedron),16); - m_polyhedron = new (mem) btConvexPolyhedron(polyhedron); - } -} bool btPolyhedralConvexShape::initializePolyhedralFeatures(int shiftVerticesByMargin) { @@ -98,71 +87,7 @@ bool btPolyhedralConvexShape::initializePolyhedralFeatures(int shiftVerticesByMa conv.compute(&orgVertices[0].getX(), sizeof(btVector3),orgVertices.size(),0.f,0.f); } -#ifndef BT_RECONSTRUCT_FACES - - int numVertices = conv.vertices.size(); - m_polyhedron->m_vertices.resize(numVertices); - for (int p=0;pm_vertices[p] = conv.vertices[p]; - } - - int v0, v1; - for (int j = 0; j < conv.faces.size(); j++) - { - btVector3 edges[3]; - int numEdges = 0; - btFace combinedFace; - const btConvexHullComputer::Edge* edge = &conv.edges[conv.faces[j]]; - v0 = edge->getSourceVertex(); - int prevVertex=v0; - combinedFace.m_indices.push_back(v0); - v1 = edge->getTargetVertex(); - while (v1 != v0) - { - - btVector3 wa = conv.vertices[prevVertex]; - btVector3 wb = conv.vertices[v1]; - btVector3 newEdge = wb-wa; - newEdge.normalize(); - if (numEdges<2) - edges[numEdges++] = newEdge; - - - //face->addIndex(v1); - combinedFace.m_indices.push_back(v1); - edge = edge->getNextEdgeOfFace(); - prevVertex = v1; - int v01 = edge->getSourceVertex(); - v1 = edge->getTargetVertex(); - - } - - btAssert(combinedFace.m_indices.size() > 2); - - btVector3 faceNormal = edges[0].cross(edges[1]); - faceNormal.normalize(); - - btScalar planeEq=1e30f; - - for (int v=0;vm_vertices[combinedFace.m_indices[v]].dot(faceNormal); - if (planeEq>eq) - { - planeEq=eq; - } - } - combinedFace.m_plane[0] = faceNormal.getX(); - combinedFace.m_plane[1] = faceNormal.getY(); - combinedFace.m_plane[2] = faceNormal.getZ(); - combinedFace.m_plane[3] = -planeEq; - - m_polyhedron->m_faces.push_back(combinedFace); - } - -#else//BT_RECONSTRUCT_FACES btAlignedObjectArray faceNormals; int numFaces = conv.faces.size(); @@ -386,9 +311,7 @@ bool btPolyhedralConvexShape::initializePolyhedralFeatures(int shiftVerticesByMa } - -#endif //BT_RECONSTRUCT_FACES - + m_polyhedron->initialize(); return true; diff --git a/extern/bullet/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.h b/extern/bullet/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.h index b7ddb6e06080..7bf8e01c1fcb 100644 --- a/extern/bullet/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.h +++ b/extern/bullet/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.h @@ -43,9 +43,6 @@ ATTRIBUTE_ALIGNED16(class) btPolyhedralConvexShape : public btConvexInternalShap ///experimental/work-in-progress virtual bool initializePolyhedralFeatures(int shiftVerticesByMargin=0); - virtual void setPolyhedralFeatures(btConvexPolyhedron& polyhedron); - - const btConvexPolyhedron* getConvexPolyhedron() const { return m_polyhedron; diff --git a/extern/bullet/src/BulletCollision/CollisionShapes/btSdfCollisionShape.cpp b/extern/bullet/src/BulletCollision/CollisionShapes/btSdfCollisionShape.cpp deleted file mode 100644 index 828acda47094..000000000000 --- a/extern/bullet/src/BulletCollision/CollisionShapes/btSdfCollisionShape.cpp +++ /dev/null @@ -1,99 +0,0 @@ -#include "btSdfCollisionShape.h" -#include "btMiniSDF.h" -#include "LinearMath/btAabbUtil2.h" - -struct btSdfCollisionShapeInternalData -{ - btVector3 m_localScaling; - btScalar m_margin; - btMiniSDF m_sdf; - - btSdfCollisionShapeInternalData() - :m_localScaling(1,1,1), - m_margin(0) - { - - } -}; - -bool btSdfCollisionShape::initializeSDF(const char* sdfData, int sizeInBytes) -{ - bool valid = m_data->m_sdf.load(sdfData, sizeInBytes); - return valid; -} -btSdfCollisionShape::btSdfCollisionShape() -{ - m_shapeType = SDF_SHAPE_PROXYTYPE; - m_data = new btSdfCollisionShapeInternalData(); - - - - //"E:/develop/bullet3/data/toys/ground_hole64_64_8.cdf");//ground_cube.cdf"); - /*unsigned int field_id=0; - Eigen::Vector3d x (1,10,1); - Eigen::Vector3d gradient; - double dist = m_data->m_sdf.interpolate(field_id, x, &gradient); - printf("dist=%g\n", dist); - */ - -} -btSdfCollisionShape::~btSdfCollisionShape() -{ - delete m_data; -} - -void btSdfCollisionShape::getAabb(const btTransform& t,btVector3& aabbMin,btVector3& aabbMax) const -{ - btAssert(m_data->m_sdf.isValid()); - btVector3 localAabbMin = m_data->m_sdf.m_domain.m_min; - btVector3 localAabbMax = m_data->m_sdf.m_domain.m_max; - btScalar margin(0); - btTransformAabb(localAabbMin,localAabbMax,margin,t,aabbMin,aabbMax); - -} - - -void btSdfCollisionShape::setLocalScaling(const btVector3& scaling) -{ - m_data->m_localScaling = scaling; -} -const btVector3& btSdfCollisionShape::getLocalScaling() const -{ - return m_data->m_localScaling; -} -void btSdfCollisionShape::calculateLocalInertia(btScalar mass,btVector3& inertia) const -{ - inertia.setValue(0,0,0); -} -const char* btSdfCollisionShape::getName()const -{ - return "btSdfCollisionShape"; -} -void btSdfCollisionShape::setMargin(btScalar margin) -{ - m_data->m_margin = margin; -} -btScalar btSdfCollisionShape::getMargin() const -{ - return m_data->m_margin; -} - -void btSdfCollisionShape::processAllTriangles(btTriangleCallback* callback,const btVector3& aabbMin,const btVector3& aabbMax) const -{ - //not yet -} - - -bool btSdfCollisionShape::queryPoint(const btVector3& ptInSDF, btScalar& distOut, btVector3& normal) -{ - int field = 0; - btVector3 grad; - double dist; - bool hasResult = m_data->m_sdf.interpolate(field,dist, ptInSDF,&grad); - if (hasResult) - { - normal.setValue(grad[0],grad[1],grad[2]); - distOut= dist; - } - return hasResult; -} diff --git a/extern/bullet/src/BulletCollision/CollisionShapes/btSdfCollisionShape.h b/extern/bullet/src/BulletCollision/CollisionShapes/btSdfCollisionShape.h deleted file mode 100644 index 6e32db9cd861..000000000000 --- a/extern/bullet/src/BulletCollision/CollisionShapes/btSdfCollisionShape.h +++ /dev/null @@ -1,30 +0,0 @@ -#ifndef BT_SDF_COLLISION_SHAPE_H -#define BT_SDF_COLLISION_SHAPE_H - -#include "btConcaveShape.h" - -class btSdfCollisionShape : public btConcaveShape -{ - struct btSdfCollisionShapeInternalData* m_data; - -public: - - btSdfCollisionShape(); - virtual ~btSdfCollisionShape(); - - bool initializeSDF(const char* sdfData, int sizeInBytes); - - virtual void getAabb(const btTransform& t,btVector3& aabbMin,btVector3& aabbMax) const; - virtual void setLocalScaling(const btVector3& scaling); - virtual const btVector3& getLocalScaling() const; - virtual void calculateLocalInertia(btScalar mass,btVector3& inertia) const; - virtual const char* getName()const; - virtual void setMargin(btScalar margin); - virtual btScalar getMargin() const; - - virtual void processAllTriangles(btTriangleCallback* callback,const btVector3& aabbMin,const btVector3& aabbMax) const; - - bool queryPoint(const btVector3& ptInSDF, btScalar& distOut, btVector3& normal); -}; - -#endif //BT_SDF_COLLISION_SHAPE_H diff --git a/extern/bullet/src/BulletCollision/CollisionShapes/btShapeHull.cpp b/extern/bullet/src/BulletCollision/CollisionShapes/btShapeHull.cpp index 9f712fe555ab..3beaf8658018 100644 --- a/extern/bullet/src/BulletCollision/CollisionShapes/btShapeHull.cpp +++ b/extern/bullet/src/BulletCollision/CollisionShapes/btShapeHull.cpp @@ -20,8 +20,6 @@ subject to the following restrictions: #include "LinearMath/btConvexHull.h" #define NUM_UNITSPHERE_POINTS 42 -#define NUM_UNITSPHERE_POINTS_HIGHRES 256 - btShapeHull::btShapeHull (const btConvexShape* shape) { @@ -38,9 +36,9 @@ btShapeHull::~btShapeHull () } bool -btShapeHull::buildHull (btScalar /*margin*/, int highres) +btShapeHull::buildHull (btScalar /*margin*/) { - int numSampleDirections = highres? NUM_UNITSPHERE_POINTS_HIGHRES:NUM_UNITSPHERE_POINTS; + int numSampleDirections = NUM_UNITSPHERE_POINTS; { int numPDA = m_shape->getNumPreferredPenetrationDirections(); if (numPDA) @@ -49,17 +47,17 @@ btShapeHull::buildHull (btScalar /*margin*/, int highres) { btVector3 norm; m_shape->getPreferredPenetrationDirection(i,norm); - getUnitSpherePoints(highres)[numSampleDirections] = norm; + getUnitSpherePoints()[numSampleDirections] = norm; numSampleDirections++; } } } - btVector3 supportPoints[NUM_UNITSPHERE_POINTS_HIGHRES+MAX_PREFERRED_PENETRATION_DIRECTIONS*2]; + btVector3 supportPoints[NUM_UNITSPHERE_POINTS+MAX_PREFERRED_PENETRATION_DIRECTIONS*2]; int i; for (i = 0; i < numSampleDirections; i++) { - supportPoints[i] = m_shape->localGetSupportingVertex(getUnitSpherePoints(highres)[i]); + supportPoints[i] = m_shape->localGetSupportingVertex(getUnitSpherePoints()[i]); } HullDesc hd; @@ -120,268 +118,9 @@ btShapeHull::numIndices () const } -btVector3* btShapeHull::getUnitSpherePoints(int highres) +btVector3* btShapeHull::getUnitSpherePoints() { - static btVector3 sUnitSpherePointsHighres[NUM_UNITSPHERE_POINTS_HIGHRES + MAX_PREFERRED_PENETRATION_DIRECTIONS * 2] = - { - btVector3(btScalar(0.997604), btScalar(0.067004), btScalar(0.017144)), - btVector3(btScalar(0.984139), btScalar(-0.086784), btScalar(-0.154427)), - btVector3(btScalar(0.971065), btScalar(0.124164), btScalar(-0.203224)), - btVector3(btScalar(0.955844), btScalar(0.291173), btScalar(-0.037704)), - btVector3(btScalar(0.957405), btScalar(0.212238), btScalar(0.195157)), - btVector3(btScalar(0.971650), btScalar(-0.012709), btScalar(0.235561)), - btVector3(btScalar(0.984920), btScalar(-0.161831), btScalar(0.059695)), - btVector3(btScalar(0.946673), btScalar(-0.299288), btScalar(-0.117536)), - btVector3(btScalar(0.922670), btScalar(-0.219186), btScalar(-0.317019)), - btVector3(btScalar(0.928134), btScalar(-0.007265), btScalar(-0.371867)), - btVector3(btScalar(0.875642), btScalar(0.198434), btScalar(-0.439988)), - btVector3(btScalar(0.908035), btScalar(0.325975), btScalar(-0.262562)), - btVector3(btScalar(0.864519), btScalar(0.488706), btScalar(-0.116755)), - btVector3(btScalar(0.893009), btScalar(0.428046), btScalar(0.137185)), - btVector3(btScalar(0.857494), btScalar(0.362137), btScalar(0.364776)), - btVector3(btScalar(0.900815), btScalar(0.132524), btScalar(0.412987)), - btVector3(btScalar(0.934964), btScalar(-0.241739), btScalar(0.259179)), - btVector3(btScalar(0.894570), btScalar(-0.103504), btScalar(0.434263)), - btVector3(btScalar(0.922085), btScalar(-0.376668), btScalar(0.086241)), - btVector3(btScalar(0.862177), btScalar(-0.499154), btScalar(-0.085330)), - btVector3(btScalar(0.861982), btScalar(-0.420218), btScalar(-0.282861)), - btVector3(btScalar(0.818076), btScalar(-0.328256), btScalar(-0.471804)), - btVector3(btScalar(0.762657), btScalar(-0.179329), btScalar(-0.621124)), - btVector3(btScalar(0.826857), btScalar(0.019760), btScalar(-0.561786)), - btVector3(btScalar(0.731434), btScalar(0.206599), btScalar(-0.649817)), - btVector3(btScalar(0.769486), btScalar(0.379052), btScalar(-0.513770)), - btVector3(btScalar(0.796806), btScalar(0.507176), btScalar(-0.328145)), - btVector3(btScalar(0.679722), btScalar(0.684101), btScalar(-0.264123)), - btVector3(btScalar(0.786854), btScalar(0.614886), btScalar(0.050912)), - btVector3(btScalar(0.769486), btScalar(0.571141), btScalar(0.285139)), - btVector3(btScalar(0.707432), btScalar(0.492789), btScalar(0.506288)), - btVector3(btScalar(0.774560), btScalar(0.268037), btScalar(0.572652)), - btVector3(btScalar(0.796220), btScalar(0.031230), btScalar(0.604077)), - btVector3(btScalar(0.837395), btScalar(-0.320285), btScalar(0.442461)), - btVector3(btScalar(0.848127), btScalar(-0.450548), btScalar(0.278307)), - btVector3(btScalar(0.775536), btScalar(-0.206354), btScalar(0.596465)), - btVector3(btScalar(0.816320), btScalar(-0.567007), btScalar(0.109469)), - btVector3(btScalar(0.741191), btScalar(-0.668690), btScalar(-0.056832)), - btVector3(btScalar(0.755632), btScalar(-0.602975), btScalar(-0.254949)), - btVector3(btScalar(0.720311), btScalar(-0.521318), btScalar(-0.457165)), - btVector3(btScalar(0.670746), btScalar(-0.386583), btScalar(-0.632835)), - btVector3(btScalar(0.587031), btScalar(-0.219769), btScalar(-0.778836)), - btVector3(btScalar(0.676015), btScalar(-0.003182), btScalar(-0.736676)), - btVector3(btScalar(0.566932), btScalar(0.186963), btScalar(-0.802064)), - btVector3(btScalar(0.618254), btScalar(0.398105), btScalar(-0.677533)), - btVector3(btScalar(0.653964), btScalar(0.575224), btScalar(-0.490933)), - btVector3(btScalar(0.525367), btScalar(0.743205), btScalar(-0.414028)), - btVector3(btScalar(0.506439), btScalar(0.836528), btScalar(-0.208885)), - btVector3(btScalar(0.651427), btScalar(0.756426), btScalar(-0.056247)), - btVector3(btScalar(0.641670), btScalar(0.745149), btScalar(0.180908)), - btVector3(btScalar(0.602643), btScalar(0.687211), btScalar(0.405180)), - btVector3(btScalar(0.516586), btScalar(0.596999), btScalar(0.613447)), - btVector3(btScalar(0.602252), btScalar(0.387801), btScalar(0.697573)), - btVector3(btScalar(0.646549), btScalar(0.153911), btScalar(0.746956)), - btVector3(btScalar(0.650842), btScalar(-0.087756), btScalar(0.753983)), - btVector3(btScalar(0.740411), btScalar(-0.497404), btScalar(0.451830)), - btVector3(btScalar(0.726946), btScalar(-0.619890), btScalar(0.295093)), - btVector3(btScalar(0.637768), btScalar(-0.313092), btScalar(0.703624)), - btVector3(btScalar(0.678942), btScalar(-0.722934), btScalar(0.126645)), - btVector3(btScalar(0.489072), btScalar(-0.867195), btScalar(-0.092942)), - btVector3(btScalar(0.622742), btScalar(-0.757541), btScalar(-0.194636)), - btVector3(btScalar(0.596788), btScalar(-0.693576), btScalar(-0.403098)), - btVector3(btScalar(0.550150), btScalar(-0.582172), btScalar(-0.598287)), - btVector3(btScalar(0.474436), btScalar(-0.429745), btScalar(-0.768101)), - btVector3(btScalar(0.372574), btScalar(-0.246016), btScalar(-0.894583)), - btVector3(btScalar(0.480095), btScalar(-0.026513), btScalar(-0.876626)), - btVector3(btScalar(0.352474), btScalar(0.177242), btScalar(-0.918787)), - btVector3(btScalar(0.441848), btScalar(0.374386), btScalar(-0.814946)), - btVector3(btScalar(0.492389), btScalar(0.582223), btScalar(-0.646693)), - btVector3(btScalar(0.343498), btScalar(0.866080), btScalar(-0.362693)), - btVector3(btScalar(0.362036), btScalar(0.745149), btScalar(-0.559639)), - btVector3(btScalar(0.334131), btScalar(0.937044), btScalar(-0.099774)), - btVector3(btScalar(0.486925), btScalar(0.871718), btScalar(0.052473)), - btVector3(btScalar(0.452776), btScalar(0.845665), btScalar(0.281820)), - btVector3(btScalar(0.399503), btScalar(0.771785), btScalar(0.494576)), - btVector3(btScalar(0.296469), btScalar(0.673018), btScalar(0.677469)), - btVector3(btScalar(0.392088), btScalar(0.479179), btScalar(0.785213)), - btVector3(btScalar(0.452190), btScalar(0.252094), btScalar(0.855286)), - btVector3(btScalar(0.478339), btScalar(0.013149), btScalar(0.877928)), - btVector3(btScalar(0.481656), btScalar(-0.219380), btScalar(0.848259)), - btVector3(btScalar(0.615327), btScalar(-0.494293), btScalar(0.613837)), - btVector3(btScalar(0.594642), btScalar(-0.650414), btScalar(0.472325)), - btVector3(btScalar(0.562249), btScalar(-0.771345), btScalar(0.297631)), - btVector3(btScalar(0.467411), btScalar(-0.437133), btScalar(0.768231)), - btVector3(btScalar(0.519513), btScalar(-0.847947), btScalar(0.103808)), - btVector3(btScalar(0.297640), btScalar(-0.938159), btScalar(-0.176288)), - btVector3(btScalar(0.446727), btScalar(-0.838615), btScalar(-0.311359)), - btVector3(btScalar(0.331790), btScalar(-0.942437), btScalar(0.040762)), - btVector3(btScalar(0.413358), btScalar(-0.748403), btScalar(-0.518259)), - btVector3(btScalar(0.347596), btScalar(-0.621640), btScalar(-0.701737)), - btVector3(btScalar(0.249831), btScalar(-0.456186), btScalar(-0.853984)), - btVector3(btScalar(0.131772), btScalar(-0.262931), btScalar(-0.955678)), - btVector3(btScalar(0.247099), btScalar(-0.042261), btScalar(-0.967975)), - btVector3(btScalar(0.113624), btScalar(0.165965), btScalar(-0.979491)), - btVector3(btScalar(0.217438), btScalar(0.374580), btScalar(-0.901220)), - btVector3(btScalar(0.307983), btScalar(0.554615), btScalar(-0.772786)), - btVector3(btScalar(0.166702), btScalar(0.953181), btScalar(-0.252021)), - btVector3(btScalar(0.172751), btScalar(0.844499), btScalar(-0.506743)), - btVector3(btScalar(0.177630), btScalar(0.711125), btScalar(-0.679876)), - btVector3(btScalar(0.120064), btScalar(0.992260), btScalar(-0.030482)), - btVector3(btScalar(0.289640), btScalar(0.949098), btScalar(0.122546)), - btVector3(btScalar(0.239879), btScalar(0.909047), btScalar(0.340377)), - btVector3(btScalar(0.181142), btScalar(0.821363), btScalar(0.540641)), - btVector3(btScalar(0.066986), btScalar(0.719097), btScalar(0.691327)), - btVector3(btScalar(0.156750), btScalar(0.545478), btScalar(0.823079)), - btVector3(btScalar(0.236172), btScalar(0.342306), btScalar(0.909353)), - btVector3(btScalar(0.277541), btScalar(0.112693), btScalar(0.953856)), - btVector3(btScalar(0.295299), btScalar(-0.121974), btScalar(0.947415)), - btVector3(btScalar(0.287883), btScalar(-0.349254), btScalar(0.891591)), - btVector3(btScalar(0.437165), btScalar(-0.634666), btScalar(0.636869)), - btVector3(btScalar(0.407113), btScalar(-0.784954), btScalar(0.466664)), - btVector3(btScalar(0.375111), btScalar(-0.888193), btScalar(0.264839)), - btVector3(btScalar(0.275394), btScalar(-0.560591), btScalar(0.780723)), - btVector3(btScalar(0.122015), btScalar(-0.992209), btScalar(-0.024821)), - btVector3(btScalar(0.087866), btScalar(-0.966156), btScalar(-0.241676)), - btVector3(btScalar(0.239489), btScalar(-0.885665), btScalar(-0.397437)), - btVector3(btScalar(0.167287), btScalar(-0.965184), btScalar(0.200817)), - btVector3(btScalar(0.201632), btScalar(-0.776789), btScalar(-0.596335)), - btVector3(btScalar(0.122015), btScalar(-0.637971), btScalar(-0.760098)), - btVector3(btScalar(0.008054), btScalar(-0.464741), btScalar(-0.885214)), - btVector3(btScalar(-0.116054), btScalar(-0.271096), btScalar(-0.955482)), - btVector3(btScalar(-0.000727), btScalar(-0.056065), btScalar(-0.998424)), - btVector3(btScalar(-0.134007), btScalar(0.152939), btScalar(-0.978905)), - btVector3(btScalar(-0.025900), btScalar(0.366026), btScalar(-0.930108)), - btVector3(btScalar(0.081231), btScalar(0.557337), btScalar(-0.826072)), - btVector3(btScalar(-0.002874), btScalar(0.917213), btScalar(-0.398023)), - btVector3(btScalar(-0.050683), btScalar(0.981761), btScalar(-0.182534)), - btVector3(btScalar(-0.040536), btScalar(0.710153), btScalar(-0.702713)), - btVector3(btScalar(-0.139081), btScalar(0.827973), btScalar(-0.543048)), - btVector3(btScalar(-0.101029), btScalar(0.994010), btScalar(0.041152)), - btVector3(btScalar(0.069328), btScalar(0.978067), btScalar(0.196133)), - btVector3(btScalar(0.023860), btScalar(0.911380), btScalar(0.410645)), - btVector3(btScalar(-0.153521), btScalar(0.736789), btScalar(0.658145)), - btVector3(btScalar(-0.070002), btScalar(0.591750), btScalar(0.802780)), - btVector3(btScalar(0.002590), btScalar(0.312948), btScalar(0.949562)), - btVector3(btScalar(0.090988), btScalar(-0.020680), btScalar(0.995627)), - btVector3(btScalar(0.088842), btScalar(-0.250099), btScalar(0.964006)), - btVector3(btScalar(0.083378), btScalar(-0.470185), btScalar(0.878318)), - btVector3(btScalar(0.240074), btScalar(-0.749764), btScalar(0.616374)), - btVector3(btScalar(0.210803), btScalar(-0.885860), btScalar(0.412987)), - btVector3(btScalar(0.077524), btScalar(-0.660524), btScalar(0.746565)), - btVector3(btScalar(-0.096736), btScalar(-0.990070), btScalar(-0.100945)), - btVector3(btScalar(-0.052634), btScalar(-0.990264), btScalar(0.127426)), - btVector3(btScalar(-0.106102), btScalar(-0.938354), btScalar(-0.328340)), - btVector3(btScalar(0.013323), btScalar(-0.863112), btScalar(-0.504596)), - btVector3(btScalar(-0.002093), btScalar(-0.936993), btScalar(0.349161)), - btVector3(btScalar(-0.106297), btScalar(-0.636610), btScalar(-0.763612)), - btVector3(btScalar(-0.229430), btScalar(-0.463769), btScalar(-0.855546)), - btVector3(btScalar(-0.245236), btScalar(-0.066175), btScalar(-0.966999)), - btVector3(btScalar(-0.351587), btScalar(-0.270513), btScalar(-0.896145)), - btVector3(btScalar(-0.370906), btScalar(0.133108), btScalar(-0.918982)), - btVector3(btScalar(-0.264360), btScalar(0.346000), btScalar(-0.900049)), - btVector3(btScalar(-0.151375), btScalar(0.543728), btScalar(-0.825291)), - btVector3(btScalar(-0.218697), btScalar(0.912741), btScalar(-0.344346)), - btVector3(btScalar(-0.274507), btScalar(0.953764), btScalar(-0.121635)), - btVector3(btScalar(-0.259677), btScalar(0.692266), btScalar(-0.673044)), - btVector3(btScalar(-0.350416), btScalar(0.798810), btScalar(-0.488786)), - btVector3(btScalar(-0.320170), btScalar(0.941127), btScalar(0.108297)), - btVector3(btScalar(-0.147667), btScalar(0.952792), btScalar(0.265034)), - btVector3(btScalar(-0.188061), btScalar(0.860636), btScalar(0.472910)), - btVector3(btScalar(-0.370906), btScalar(0.739900), btScalar(0.560941)), - btVector3(btScalar(-0.297143), btScalar(0.585334), btScalar(0.754178)), - btVector3(btScalar(-0.189622), btScalar(0.428241), btScalar(0.883393)), - btVector3(btScalar(-0.091272), btScalar(0.098695), btScalar(0.990747)), - btVector3(btScalar(-0.256945), btScalar(0.228375), btScalar(0.938827)), - btVector3(btScalar(-0.111761), btScalar(-0.133251), btScalar(0.984696)), - btVector3(btScalar(-0.118006), btScalar(-0.356253), btScalar(0.926725)), - btVector3(btScalar(-0.119372), btScalar(-0.563896), btScalar(0.817029)), - btVector3(btScalar(0.041228), btScalar(-0.833949), btScalar(0.550010)), - btVector3(btScalar(-0.121909), btScalar(-0.736543), btScalar(0.665172)), - btVector3(btScalar(-0.307681), btScalar(-0.931160), btScalar(-0.195026)), - btVector3(btScalar(-0.283679), btScalar(-0.957990), btScalar(0.041348)), - btVector3(btScalar(-0.227284), btScalar(-0.935243), btScalar(0.270890)), - btVector3(btScalar(-0.293436), btScalar(-0.858252), btScalar(-0.420860)), - btVector3(btScalar(-0.175767), btScalar(-0.780677), btScalar(-0.599262)), - btVector3(btScalar(-0.170108), btScalar(-0.858835), btScalar(0.482865)), - btVector3(btScalar(-0.332854), btScalar(-0.635055), btScalar(-0.696857)), - btVector3(btScalar(-0.447791), btScalar(-0.445299), btScalar(-0.775128)), - btVector3(btScalar(-0.470622), btScalar(-0.074146), btScalar(-0.879164)), - btVector3(btScalar(-0.639417), btScalar(-0.340505), btScalar(-0.689049)), - btVector3(btScalar(-0.598438), btScalar(0.104722), btScalar(-0.794256)), - btVector3(btScalar(-0.488575), btScalar(0.307699), btScalar(-0.816313)), - btVector3(btScalar(-0.379882), btScalar(0.513592), btScalar(-0.769077)), - btVector3(btScalar(-0.425740), btScalar(0.862775), btScalar(-0.272516)), - btVector3(btScalar(-0.480769), btScalar(0.875412), btScalar(-0.048439)), - btVector3(btScalar(-0.467890), btScalar(0.648716), btScalar(-0.600043)), - btVector3(btScalar(-0.543799), btScalar(0.730956), btScalar(-0.411881)), - btVector3(btScalar(-0.516284), btScalar(0.838277), btScalar(0.174076)), - btVector3(btScalar(-0.353343), btScalar(0.876384), btScalar(0.326519)), - btVector3(btScalar(-0.572875), btScalar(0.614497), btScalar(0.542007)), - btVector3(btScalar(-0.503600), btScalar(0.497261), btScalar(0.706161)), - btVector3(btScalar(-0.530920), btScalar(0.754870), btScalar(0.384685)), - btVector3(btScalar(-0.395884), btScalar(0.366414), btScalar(0.841818)), - btVector3(btScalar(-0.300656), btScalar(0.001678), btScalar(0.953661)), - btVector3(btScalar(-0.461060), btScalar(0.146912), btScalar(0.875000)), - btVector3(btScalar(-0.315486), btScalar(-0.232212), btScalar(0.919893)), - btVector3(btScalar(-0.323682), btScalar(-0.449187), btScalar(0.832644)), - btVector3(btScalar(-0.318999), btScalar(-0.639527), btScalar(0.699134)), - btVector3(btScalar(-0.496771), btScalar(-0.866029), btScalar(-0.055271)), - btVector3(btScalar(-0.496771), btScalar(-0.816257), btScalar(-0.294377)), - btVector3(btScalar(-0.456377), btScalar(-0.869528), btScalar(0.188130)), - btVector3(btScalar(-0.380858), btScalar(-0.827144), btScalar(0.412792)), - btVector3(btScalar(-0.449352), btScalar(-0.727405), btScalar(-0.518259)), - btVector3(btScalar(-0.570533), btScalar(-0.551064), btScalar(-0.608632)), - btVector3(btScalar(-0.656394), btScalar(-0.118280), btScalar(-0.744874)), - btVector3(btScalar(-0.756696), btScalar(-0.438105), btScalar(-0.484882)), - btVector3(btScalar(-0.801773), btScalar(-0.204798), btScalar(-0.561005)), - btVector3(btScalar(-0.785186), btScalar(0.038618), btScalar(-0.617805)), - btVector3(btScalar(-0.709082), btScalar(0.262399), btScalar(-0.654306)), - btVector3(btScalar(-0.583412), btScalar(0.462265), btScalar(-0.667383)), - btVector3(btScalar(-0.616001), btScalar(0.761286), btScalar(-0.201272)), - btVector3(btScalar(-0.660687), btScalar(0.750204), btScalar(0.020072)), - btVector3(btScalar(-0.744987), btScalar(0.435823), btScalar(-0.504791)), - btVector3(btScalar(-0.713765), btScalar(0.605554), btScalar(-0.351373)), - btVector3(btScalar(-0.686251), btScalar(0.687600), btScalar(0.236927)), - btVector3(btScalar(-0.680201), btScalar(0.429407), btScalar(0.593732)), - btVector3(btScalar(-0.733474), btScalar(0.546450), btScalar(0.403814)), - btVector3(btScalar(-0.591023), btScalar(0.292923), btScalar(0.751445)), - btVector3(btScalar(-0.500283), btScalar(-0.080757), btScalar(0.861922)), - btVector3(btScalar(-0.643710), btScalar(0.070115), btScalar(0.761985)), - btVector3(btScalar(-0.506332), btScalar(-0.308425), btScalar(0.805122)), - btVector3(btScalar(-0.503015), btScalar(-0.509847), btScalar(0.697573)), - btVector3(btScalar(-0.482525), btScalar(-0.682105), btScalar(0.549229)), - btVector3(btScalar(-0.680396), btScalar(-0.716323), btScalar(-0.153451)), - btVector3(btScalar(-0.658346), btScalar(-0.746264), btScalar(0.097562)), - btVector3(btScalar(-0.653272), btScalar(-0.646915), btScalar(-0.392948)), - btVector3(btScalar(-0.590828), btScalar(-0.732655), btScalar(0.337645)), - btVector3(btScalar(-0.819140), btScalar(-0.518013), btScalar(-0.246166)), - btVector3(btScalar(-0.900513), btScalar(-0.282178), btScalar(-0.330487)), - btVector3(btScalar(-0.914953), btScalar(-0.028652), btScalar(-0.402122)), - btVector3(btScalar(-0.859924), btScalar(0.220209), btScalar(-0.459898)), - btVector3(btScalar(-0.777185), btScalar(0.613720), btScalar(-0.137836)), - btVector3(btScalar(-0.805285), btScalar(0.586889), btScalar(0.082728)), - btVector3(btScalar(-0.872413), btScalar(0.406077), btScalar(-0.271735)), - btVector3(btScalar(-0.859339), btScalar(0.448072), btScalar(0.246101)), - btVector3(btScalar(-0.757671), btScalar(0.216320), btScalar(0.615594)), - btVector3(btScalar(-0.826165), btScalar(0.348139), btScalar(0.442851)), - btVector3(btScalar(-0.671810), btScalar(-0.162803), btScalar(0.722557)), - btVector3(btScalar(-0.796504), btScalar(-0.004543), btScalar(0.604468)), - btVector3(btScalar(-0.676298), btScalar(-0.378223), btScalar(0.631794)), - btVector3(btScalar(-0.668883), btScalar(-0.558258), btScalar(0.490673)), - btVector3(btScalar(-0.821287), btScalar(-0.570118), btScalar(0.006994)), - btVector3(btScalar(-0.767428), btScalar(-0.587810), btScalar(0.255470)), - btVector3(btScalar(-0.933296), btScalar(-0.349837), btScalar(-0.079865)), - btVector3(btScalar(-0.982667), btScalar(-0.100393), btScalar(-0.155208)), - btVector3(btScalar(-0.961396), btScalar(0.160910), btScalar(-0.222938)), - btVector3(btScalar(-0.934858), btScalar(0.354555), btScalar(-0.006864)), - btVector3(btScalar(-0.941687), btScalar(0.229736), btScalar(0.245711)), - btVector3(btScalar(-0.884317), btScalar(0.131552), btScalar(0.447536)), - btVector3(btScalar(-0.810359), btScalar(-0.219769), btScalar(0.542788)), - btVector3(btScalar(-0.915929), btScalar(-0.210048), btScalar(0.341743)), - btVector3(btScalar(-0.816799), btScalar(-0.407192), btScalar(0.408303)), - btVector3(btScalar(-0.903050), btScalar(-0.392416), btScalar(0.174076)), - btVector3(btScalar(-0.980325), btScalar(-0.170969), btScalar(0.096586)), - btVector3(btScalar(-0.995936), btScalar(0.084891), btScalar(0.029441)), - btVector3(btScalar(-0.960031), btScalar(0.002650), btScalar(0.279283)), - }; - static btVector3 sUnitSpherePoints[NUM_UNITSPHERE_POINTS + MAX_PREFERRED_PENETRATION_DIRECTIONS * 2] = + static btVector3 sUnitSpherePoints[NUM_UNITSPHERE_POINTS+MAX_PREFERRED_PENETRATION_DIRECTIONS*2] = { btVector3(btScalar(0.000000) , btScalar(-0.000000),btScalar(-1.000000)), btVector3(btScalar(0.723608) , btScalar(-0.525725),btScalar(-0.447219)), @@ -426,8 +165,6 @@ btVector3* btShapeHull::getUnitSpherePoints(int highres) btVector3(btScalar(-0.425323) , btScalar(0.309011),btScalar(0.850654)), btVector3(btScalar(0.162456) , btScalar(0.499995),btScalar(0.850654)) }; - if (highres) - return sUnitSpherePointsHighres; return sUnitSpherePoints; } diff --git a/extern/bullet/src/BulletCollision/CollisionShapes/btShapeHull.h b/extern/bullet/src/BulletCollision/CollisionShapes/btShapeHull.h index 78ea4b65011f..e959f198b69a 100644 --- a/extern/bullet/src/BulletCollision/CollisionShapes/btShapeHull.h +++ b/extern/bullet/src/BulletCollision/CollisionShapes/btShapeHull.h @@ -34,7 +34,7 @@ ATTRIBUTE_ALIGNED16(class) btShapeHull unsigned int m_numIndices; const btConvexShape* m_shape; - static btVector3* getUnitSpherePoints(int highres=0); + static btVector3* getUnitSpherePoints(); public: BT_DECLARE_ALIGNED_ALLOCATOR(); @@ -42,7 +42,7 @@ ATTRIBUTE_ALIGNED16(class) btShapeHull btShapeHull (const btConvexShape* shape); ~btShapeHull (); - bool buildHull (btScalar margin, int highres=0); + bool buildHull (btScalar margin); int numTriangles () const; int numVertices () const; diff --git a/extern/bullet/src/BulletCollision/CollisionShapes/btStaticPlaneShape.cpp b/extern/bullet/src/BulletCollision/CollisionShapes/btStaticPlaneShape.cpp index b5e0e716d487..d17141e3f205 100644 --- a/extern/bullet/src/BulletCollision/CollisionShapes/btStaticPlaneShape.cpp +++ b/extern/bullet/src/BulletCollision/CollisionShapes/btStaticPlaneShape.cpp @@ -69,6 +69,8 @@ void btStaticPlaneShape::processAllTriangles(btTriangleCallback* callback,const //tangentDir0/tangentDir1 can be precalculated btPlaneSpace1(m_planeNormal,tangentDir0,tangentDir1); + btVector3 supVertex0,supVertex1; + btVector3 projectedCenter = center - (m_planeNormal.dot(center) - m_planeConstant)*m_planeNormal; btVector3 triangle[3]; diff --git a/extern/bullet/src/BulletCollision/CollisionShapes/btTriangleIndexVertexArray.h b/extern/bullet/src/BulletCollision/CollisionShapes/btTriangleIndexVertexArray.h index b7a6f74361f1..9e1544e87a4c 100644 --- a/extern/bullet/src/BulletCollision/CollisionShapes/btTriangleIndexVertexArray.h +++ b/extern/bullet/src/BulletCollision/CollisionShapes/btTriangleIndexVertexArray.h @@ -63,7 +63,7 @@ typedef btAlignedObjectArray IndexedMeshArray; ///The btTriangleIndexVertexArray allows to access multiple triangle meshes, by indexing into existing triangle/index arrays. ///Additional meshes can be added using addIndexedMesh -///No duplicate is made of the vertex/index data, it only indexes into external vertex/index arrays. +///No duplcate is made of the vertex/index data, it only indexes into external vertex/index arrays. ///So keep those arrays around during the lifetime of this btTriangleIndexVertexArray. ATTRIBUTE_ALIGNED16( class) btTriangleIndexVertexArray : public btStridingMeshInterface { diff --git a/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.cpp b/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.cpp index 3481fec85060..940282f5762a 100644 --- a/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.cpp +++ b/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.cpp @@ -113,7 +113,12 @@ bool btContinuousConvexCollision::calcTimeOfImpact( if ((relLinVelocLength+maxAngularProjectedVelocity) == 0.f) return false; + + btScalar lambda = btScalar(0.); + btVector3 v(1,0,0); + + int maxIter = MAX_ITERATIONS; btVector3 n; n.setValue(btScalar(0.),btScalar(0.),btScalar(0.)); @@ -132,7 +137,8 @@ bool btContinuousConvexCollision::calcTimeOfImpact( btPointCollector pointCollector1; - { + { + computeClosestPoints(fromA,fromB,pointCollector1); hasResult = pointCollector1.m_hasResult; @@ -166,20 +172,28 @@ bool btContinuousConvexCollision::calcTimeOfImpact( dLambda = dist / (projectedLinearVelocity+ maxAngularProjectedVelocity); - lambda += dLambda; + + + lambda = lambda + dLambda; - if (lambda > btScalar(1.) || lambda < btScalar(0.)) + if (lambda > btScalar(1.)) return false; + if (lambda < btScalar(0.)) + return false; + + //todo: next check with relative epsilon if (lambda <= lastLambda) { return false; //n.setValue(0,0,0); - //break; + break; } lastLambda = lambda; + + //interpolate to next lambda btTransform interpolatedTransA,interpolatedTransB,relativeTrans; @@ -209,7 +223,7 @@ bool btContinuousConvexCollision::calcTimeOfImpact( } numIter++; - if (numIter > MAX_ITERATIONS) + if (numIter > maxIter) { result.reportFailure(-2, numIter); return false; @@ -223,5 +237,6 @@ bool btContinuousConvexCollision::calcTimeOfImpact( } return false; + } diff --git a/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.h b/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.h index 528b5e010143..bdc0572f75af 100644 --- a/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.h +++ b/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.h @@ -25,7 +25,7 @@ class btStaticPlaneShape; /// btContinuousConvexCollision implements angular and linear time of impact for convex objects. /// Based on Brian Mirtich's Conservative Advancement idea (PhD thesis). -/// Algorithm operates in worldspace, in order to keep in between motion globally consistent. +/// Algorithm operates in worldspace, in order to keep inbetween motion globally consistent. /// It uses GJK at the moment. Future improvement would use minkowski sum / supporting vertex, merging innerloops class btContinuousConvexCollision : public btConvexCast { diff --git a/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.cpp b/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.cpp index 2fca19292a64..572ec36f5639 100644 --- a/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.cpp +++ b/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.cpp @@ -21,64 +21,46 @@ subject to the following restrictions: #include "BulletCollision/NarrowPhaseCollision/btGjkEpa2.h" -bool btGjkEpaPenetrationDepthSolver::calcPenDepth(btSimplexSolverInterface& simplexSolver, - const btConvexShape* pConvexA, const btConvexShape* pConvexB, - const btTransform& transformA, const btTransform& transformB, - btVector3& v, btVector3& wWitnessOnA, btVector3& wWitnessOnB, - class btIDebugDraw* debugDraw) +bool btGjkEpaPenetrationDepthSolver::calcPenDepth( btSimplexSolverInterface& simplexSolver, + const btConvexShape* pConvexA, const btConvexShape* pConvexB, + const btTransform& transformA, const btTransform& transformB, + btVector3& v, btVector3& wWitnessOnA, btVector3& wWitnessOnB, + class btIDebugDraw* debugDraw) { (void)debugDraw; (void)v; (void)simplexSolver; - btVector3 guessVectors[] = { - btVector3(transformB.getOrigin() - transformA.getOrigin()), - btVector3(transformA.getOrigin() - transformB.getOrigin()), - btVector3(0, 0, 1), - btVector3(0, 1, 0), - btVector3(1, 0, 0), - btVector3(1, 1, 0), - btVector3(1, 1, 1), - btVector3(0, 1, 1), - btVector3(1, 0, 1), - }; +// const btScalar radialmargin(btScalar(0.)); + + btVector3 guessVector(transformB.getOrigin()-transformA.getOrigin()); + btGjkEpaSolver2::sResults results; + - int numVectors = sizeof(guessVectors) / sizeof(btVector3); - - for (int i = 0; i < numVectors; i++) + if(btGjkEpaSolver2::Penetration(pConvexA,transformA, + pConvexB,transformB, + guessVector,results)) + + { + // debugDraw->drawLine(results.witnesses[1],results.witnesses[1]+results.normal,btVector3(255,0,0)); + //resultOut->addContactPoint(results.normal,results.witnesses[1],-results.depth); + wWitnessOnA = results.witnesses[0]; + wWitnessOnB = results.witnesses[1]; + v = results.normal; + return true; + } else { - simplexSolver.reset(); - btVector3 guessVector = guessVectors[i]; - - btGjkEpaSolver2::sResults results; - - if (btGjkEpaSolver2::Penetration(pConvexA, transformA, - pConvexB, transformB, - guessVector, results)) - + if(btGjkEpaSolver2::Distance(pConvexA,transformA,pConvexB,transformB,guessVector,results)) { wWitnessOnA = results.witnesses[0]; wWitnessOnB = results.witnesses[1]; v = results.normal; - return true; - } - else - { - if (btGjkEpaSolver2::Distance(pConvexA, transformA, pConvexB, transformB, guessVector, results)) - { - wWitnessOnA = results.witnesses[0]; - wWitnessOnB = results.witnesses[1]; - v = results.normal; - return false; - } + return false; } } - //failed to find a distance/penetration - wWitnessOnA.setValue(0, 0, 0); - wWitnessOnB.setValue(0, 0, 0); - v.setValue(0, 0, 0); return false; } + diff --git a/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.cpp b/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.cpp index 4d29089a4a08..257b026d9bbd 100644 --- a/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.cpp +++ b/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.cpp @@ -32,7 +32,7 @@ subject to the following restrictions: //must be above the machine epsilon #ifdef BT_USE_DOUBLE_PRECISION #define REL_ERROR2 btScalar(1.0e-12) - btScalar gGjkEpaPenetrationTolerance = 1.0e-12; + btScalar gGjkEpaPenetrationTolerance = 1e-7; #else #define REL_ERROR2 btScalar(1.0e-6) btScalar gGjkEpaPenetrationTolerance = 0.001; diff --git a/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.cpp b/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.cpp index 9603a8bbdcae..23aaece22b30 100644 --- a/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.cpp +++ b/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.cpp @@ -16,13 +16,7 @@ subject to the following restrictions: #include "btPersistentManifold.h" #include "LinearMath/btTransform.h" -#include "LinearMath/btSerializer.h" -#ifdef BT_USE_DOUBLE_PRECISION -#define btCollisionObjectData btCollisionObjectDoubleData -#else -#define btCollisionObjectData btCollisionObjectFloatData -#endif btScalar gContactBreakingThreshold = btScalar(0.02); ContactDestroyedCallback gContactDestroyedCallback = 0; @@ -39,8 +33,6 @@ btPersistentManifold::btPersistentManifold() m_body0(0), m_body1(0), m_cachedPoints (0), -m_companionIdA(0), -m_companionIdB(0), m_index1a(0) { } @@ -311,149 +303,6 @@ void btPersistentManifold::refreshContactPoints(const btTransform& trA,const btT } -int btPersistentManifold::calculateSerializeBufferSize() const -{ - return sizeof(btPersistentManifoldData); -} - -const char* btPersistentManifold::serialize(const class btPersistentManifold* manifold, void* dataBuffer, class btSerializer* serializer) const -{ - btPersistentManifoldData* dataOut = (btPersistentManifoldData*)dataBuffer; - memset(dataOut, 0, sizeof(btPersistentManifoldData)); - - dataOut->m_body0 = (btCollisionObjectData*)serializer->getUniquePointer((void*)manifold->getBody0()); - dataOut->m_body1 = (btCollisionObjectData*)serializer->getUniquePointer((void*)manifold->getBody1()); - dataOut->m_contactBreakingThreshold = manifold->getContactBreakingThreshold(); - dataOut->m_contactProcessingThreshold = manifold->getContactProcessingThreshold(); - dataOut->m_numCachedPoints = manifold->getNumContacts(); - dataOut->m_companionIdA = manifold->m_companionIdA; - dataOut->m_companionIdB = manifold->m_companionIdB; - dataOut->m_index1a = manifold->m_index1a; - dataOut->m_objectType = manifold->m_objectType; - - for (int i = 0; i < this->getNumContacts(); i++) - { - const btManifoldPoint& pt = manifold->getContactPoint(i); - dataOut->m_pointCacheAppliedImpulse[i] = pt.m_appliedImpulse; - dataOut->m_pointCacheAppliedImpulseLateral1[i] = pt.m_appliedImpulseLateral1; - dataOut->m_pointCacheAppliedImpulseLateral2[i] = pt.m_appliedImpulseLateral2; - pt.m_localPointA.serialize(dataOut->m_pointCacheLocalPointA[i]); - pt.m_localPointB.serialize(dataOut->m_pointCacheLocalPointB[i]); - pt.m_normalWorldOnB.serialize(dataOut->m_pointCacheNormalWorldOnB[i]); - dataOut->m_pointCacheDistance[i] = pt.m_distance1; - dataOut->m_pointCacheCombinedContactDamping1[i] = pt.m_combinedContactDamping1; - dataOut->m_pointCacheCombinedContactStiffness1[i] = pt.m_combinedContactStiffness1; - dataOut->m_pointCacheLifeTime[i] = pt.m_lifeTime; - dataOut->m_pointCacheFrictionCFM[i] = pt.m_frictionCFM; - dataOut->m_pointCacheContactERP[i] = pt.m_contactERP; - dataOut->m_pointCacheContactCFM[i] = pt.m_contactCFM; - dataOut->m_pointCacheContactPointFlags[i] = pt.m_contactPointFlags; - dataOut->m_pointCacheIndex0[i] = pt.m_index0; - dataOut->m_pointCacheIndex1[i] = pt.m_index1; - dataOut->m_pointCachePartId0[i] = pt.m_partId0; - dataOut->m_pointCachePartId1[i] = pt.m_partId1; - pt.m_positionWorldOnA.serialize(dataOut->m_pointCachePositionWorldOnA[i]); - pt.m_positionWorldOnB.serialize(dataOut->m_pointCachePositionWorldOnB[i]); - dataOut->m_pointCacheCombinedFriction[i] = pt.m_combinedFriction; - pt.m_lateralFrictionDir1.serialize(dataOut->m_pointCacheLateralFrictionDir1[i]); - pt.m_lateralFrictionDir2.serialize(dataOut->m_pointCacheLateralFrictionDir2[i]); - dataOut->m_pointCacheCombinedRollingFriction[i] = pt.m_combinedRollingFriction; - dataOut->m_pointCacheCombinedSpinningFriction[i] = pt.m_combinedSpinningFriction; - dataOut->m_pointCacheCombinedRestitution[i] = pt.m_combinedRestitution; - dataOut->m_pointCacheContactMotion1[i] = pt.m_contactMotion1; - dataOut->m_pointCacheContactMotion2[i] = pt.m_contactMotion2; - } - return btPersistentManifoldDataName; -} - -void btPersistentManifold::deSerialize(const struct btPersistentManifoldDoubleData* manifoldDataPtr) -{ - m_contactBreakingThreshold = manifoldDataPtr->m_contactBreakingThreshold; - m_contactProcessingThreshold = manifoldDataPtr->m_contactProcessingThreshold; - m_cachedPoints = manifoldDataPtr->m_numCachedPoints; - m_companionIdA = manifoldDataPtr->m_companionIdA; - m_companionIdB = manifoldDataPtr->m_companionIdB; - //m_index1a = manifoldDataPtr->m_index1a; - m_objectType = manifoldDataPtr->m_objectType; - - for (int i = 0; i < this->getNumContacts(); i++) - { - btManifoldPoint& pt = m_pointCache[i]; - - pt.m_appliedImpulse = manifoldDataPtr->m_pointCacheAppliedImpulse[i]; - pt.m_appliedImpulseLateral1 = manifoldDataPtr->m_pointCacheAppliedImpulseLateral1[i]; - pt.m_appliedImpulseLateral2 = manifoldDataPtr->m_pointCacheAppliedImpulseLateral2[i]; - pt.m_localPointA.deSerializeDouble(manifoldDataPtr->m_pointCacheLocalPointA[i]); - pt.m_localPointB.deSerializeDouble(manifoldDataPtr->m_pointCacheLocalPointB[i]); - pt.m_normalWorldOnB.deSerializeDouble(manifoldDataPtr->m_pointCacheNormalWorldOnB[i]); - pt.m_distance1 = manifoldDataPtr->m_pointCacheDistance[i]; - pt.m_combinedContactDamping1 = manifoldDataPtr->m_pointCacheCombinedContactDamping1[i]; - pt.m_combinedContactStiffness1 = manifoldDataPtr->m_pointCacheCombinedContactStiffness1[i]; - pt.m_lifeTime = manifoldDataPtr->m_pointCacheLifeTime[i]; - pt.m_frictionCFM = manifoldDataPtr->m_pointCacheFrictionCFM[i]; - pt.m_contactERP = manifoldDataPtr->m_pointCacheContactERP[i]; - pt.m_contactCFM = manifoldDataPtr->m_pointCacheContactCFM[i]; - pt.m_contactPointFlags = manifoldDataPtr->m_pointCacheContactPointFlags[i]; - pt.m_index0 = manifoldDataPtr->m_pointCacheIndex0[i]; - pt.m_index1 = manifoldDataPtr->m_pointCacheIndex1[i]; - pt.m_partId0 = manifoldDataPtr->m_pointCachePartId0[i]; - pt.m_partId1 = manifoldDataPtr->m_pointCachePartId1[i]; - pt.m_positionWorldOnA.deSerializeDouble(manifoldDataPtr->m_pointCachePositionWorldOnA[i]); - pt.m_positionWorldOnB.deSerializeDouble(manifoldDataPtr->m_pointCachePositionWorldOnB[i]); - pt.m_combinedFriction = manifoldDataPtr->m_pointCacheCombinedFriction[i]; - pt.m_lateralFrictionDir1.deSerializeDouble(manifoldDataPtr->m_pointCacheLateralFrictionDir1[i]); - pt.m_lateralFrictionDir2.deSerializeDouble(manifoldDataPtr->m_pointCacheLateralFrictionDir2[i]); - pt.m_combinedRollingFriction = manifoldDataPtr->m_pointCacheCombinedRollingFriction[i]; - pt.m_combinedSpinningFriction = manifoldDataPtr->m_pointCacheCombinedSpinningFriction[i]; - pt.m_combinedRestitution = manifoldDataPtr->m_pointCacheCombinedRestitution[i]; - pt.m_contactMotion1 = manifoldDataPtr->m_pointCacheContactMotion1[i]; - pt.m_contactMotion2 = manifoldDataPtr->m_pointCacheContactMotion2[i]; - } -} -void btPersistentManifold::deSerialize(const struct btPersistentManifoldFloatData* manifoldDataPtr) -{ - m_contactBreakingThreshold = manifoldDataPtr->m_contactBreakingThreshold; - m_contactProcessingThreshold = manifoldDataPtr->m_contactProcessingThreshold; - m_cachedPoints = manifoldDataPtr->m_numCachedPoints; - m_companionIdA = manifoldDataPtr->m_companionIdA; - m_companionIdB = manifoldDataPtr->m_companionIdB; - //m_index1a = manifoldDataPtr->m_index1a; - m_objectType = manifoldDataPtr->m_objectType; - - for (int i = 0; i < this->getNumContacts(); i++) - { - btManifoldPoint& pt = m_pointCache[i]; - - pt.m_appliedImpulse = manifoldDataPtr->m_pointCacheAppliedImpulse[i]; - pt.m_appliedImpulseLateral1 = manifoldDataPtr->m_pointCacheAppliedImpulseLateral1[i]; - pt.m_appliedImpulseLateral2 = manifoldDataPtr->m_pointCacheAppliedImpulseLateral2[i]; - pt.m_localPointA.deSerialize(manifoldDataPtr->m_pointCacheLocalPointA[i]); - pt.m_localPointB.deSerialize(manifoldDataPtr->m_pointCacheLocalPointB[i]); - pt.m_normalWorldOnB.deSerialize(manifoldDataPtr->m_pointCacheNormalWorldOnB[i]); - pt.m_distance1 = manifoldDataPtr->m_pointCacheDistance[i]; - pt.m_combinedContactDamping1 = manifoldDataPtr->m_pointCacheCombinedContactDamping1[i]; - pt.m_combinedContactStiffness1 = manifoldDataPtr->m_pointCacheCombinedContactStiffness1[i]; - pt.m_lifeTime = manifoldDataPtr->m_pointCacheLifeTime[i]; - pt.m_frictionCFM = manifoldDataPtr->m_pointCacheFrictionCFM[i]; - pt.m_contactERP = manifoldDataPtr->m_pointCacheContactERP[i]; - pt.m_contactCFM = manifoldDataPtr->m_pointCacheContactCFM[i]; - pt.m_contactPointFlags = manifoldDataPtr->m_pointCacheContactPointFlags[i]; - pt.m_index0 = manifoldDataPtr->m_pointCacheIndex0[i]; - pt.m_index1 = manifoldDataPtr->m_pointCacheIndex1[i]; - pt.m_partId0 = manifoldDataPtr->m_pointCachePartId0[i]; - pt.m_partId1 = manifoldDataPtr->m_pointCachePartId1[i]; - pt.m_positionWorldOnA.deSerialize(manifoldDataPtr->m_pointCachePositionWorldOnA[i]); - pt.m_positionWorldOnB.deSerialize(manifoldDataPtr->m_pointCachePositionWorldOnB[i]); - pt.m_combinedFriction = manifoldDataPtr->m_pointCacheCombinedFriction[i]; - pt.m_lateralFrictionDir1.deSerialize(manifoldDataPtr->m_pointCacheLateralFrictionDir1[i]); - pt.m_lateralFrictionDir2.deSerialize(manifoldDataPtr->m_pointCacheLateralFrictionDir2[i]); - pt.m_combinedRollingFriction = manifoldDataPtr->m_pointCacheCombinedRollingFriction[i]; - pt.m_combinedSpinningFriction = manifoldDataPtr->m_pointCacheCombinedSpinningFriction[i]; - pt.m_combinedRestitution = manifoldDataPtr->m_pointCacheCombinedRestitution[i]; - pt.m_contactMotion1 = manifoldDataPtr->m_pointCacheContactMotion1[i]; - pt.m_contactMotion2 = manifoldDataPtr->m_pointCacheContactMotion2[i]; - } -} \ No newline at end of file diff --git a/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.h b/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.h index 67be0c48eba9..f872c8e1c9f3 100644 --- a/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.h +++ b/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.h @@ -24,8 +24,6 @@ class btCollisionObject; #include "LinearMath/btAlignedAllocator.h" struct btCollisionResult; -struct btCollisionObjectDoubleData; -struct btCollisionObjectFloatData; ///maximum contact breaking and merging threshold extern btScalar gContactBreakingThreshold; @@ -97,10 +95,7 @@ ATTRIBUTE_ALIGNED16( class) btPersistentManifold : public btTypedObject : btTypedObject(BT_PERSISTENT_MANIFOLD_TYPE), m_body0(body0),m_body1(body1),m_cachedPoints(0), m_contactBreakingThreshold(contactBreakingThreshold), - m_contactProcessingThreshold(contactProcessingThreshold), - m_companionIdA(0), - m_companionIdB(0), - m_index1a(0) + m_contactProcessingThreshold(contactProcessingThreshold) { } @@ -261,115 +256,10 @@ ATTRIBUTE_ALIGNED16( class) btPersistentManifold : public btTypedObject m_cachedPoints = 0; } - int calculateSerializeBufferSize() const; - const char* serialize(const class btPersistentManifold* manifold, void* dataBuffer, class btSerializer* serializer) const; - void deSerialize(const struct btPersistentManifoldDoubleData* manifoldDataPtr); - void deSerialize(const struct btPersistentManifoldFloatData* manifoldDataPtr); -}; - - - -struct btPersistentManifoldDoubleData -{ - btVector3DoubleData m_pointCacheLocalPointA[4]; - btVector3DoubleData m_pointCacheLocalPointB[4]; - btVector3DoubleData m_pointCachePositionWorldOnA[4]; - btVector3DoubleData m_pointCachePositionWorldOnB[4]; - btVector3DoubleData m_pointCacheNormalWorldOnB[4]; - btVector3DoubleData m_pointCacheLateralFrictionDir1[4]; - btVector3DoubleData m_pointCacheLateralFrictionDir2[4]; - double m_pointCacheDistance[4]; - double m_pointCacheAppliedImpulse[4]; - double m_pointCacheCombinedFriction[4]; - double m_pointCacheCombinedRollingFriction[4]; - double m_pointCacheCombinedSpinningFriction[4]; - double m_pointCacheCombinedRestitution[4]; - int m_pointCachePartId0[4]; - int m_pointCachePartId1[4]; - int m_pointCacheIndex0[4]; - int m_pointCacheIndex1[4]; - int m_pointCacheContactPointFlags[4]; - double m_pointCacheAppliedImpulseLateral1[4]; - double m_pointCacheAppliedImpulseLateral2[4]; - double m_pointCacheContactMotion1[4]; - double m_pointCacheContactMotion2[4]; - double m_pointCacheContactCFM[4]; - double m_pointCacheCombinedContactStiffness1[4]; - double m_pointCacheContactERP[4]; - double m_pointCacheCombinedContactDamping1[4]; - double m_pointCacheFrictionCFM[4]; - int m_pointCacheLifeTime[4]; - - int m_numCachedPoints; - int m_companionIdA; - int m_companionIdB; - int m_index1a; - - int m_objectType; - double m_contactBreakingThreshold; - double m_contactProcessingThreshold; - int m_padding; - - btCollisionObjectDoubleData *m_body0; - btCollisionObjectDoubleData *m_body1; -}; - - -struct btPersistentManifoldFloatData -{ - btVector3FloatData m_pointCacheLocalPointA[4]; - btVector3FloatData m_pointCacheLocalPointB[4]; - btVector3FloatData m_pointCachePositionWorldOnA[4]; - btVector3FloatData m_pointCachePositionWorldOnB[4]; - btVector3FloatData m_pointCacheNormalWorldOnB[4]; - btVector3FloatData m_pointCacheLateralFrictionDir1[4]; - btVector3FloatData m_pointCacheLateralFrictionDir2[4]; - float m_pointCacheDistance[4]; - float m_pointCacheAppliedImpulse[4]; - float m_pointCacheCombinedFriction[4]; - float m_pointCacheCombinedRollingFriction[4]; - float m_pointCacheCombinedSpinningFriction[4]; - float m_pointCacheCombinedRestitution[4]; - int m_pointCachePartId0[4]; - int m_pointCachePartId1[4]; - int m_pointCacheIndex0[4]; - int m_pointCacheIndex1[4]; - int m_pointCacheContactPointFlags[4]; - float m_pointCacheAppliedImpulseLateral1[4]; - float m_pointCacheAppliedImpulseLateral2[4]; - float m_pointCacheContactMotion1[4]; - float m_pointCacheContactMotion2[4]; - float m_pointCacheContactCFM[4]; - float m_pointCacheCombinedContactStiffness1[4]; - float m_pointCacheContactERP[4]; - float m_pointCacheCombinedContactDamping1[4]; - float m_pointCacheFrictionCFM[4]; - int m_pointCacheLifeTime[4]; - - int m_numCachedPoints; - int m_companionIdA; - int m_companionIdB; - int m_index1a; - - int m_objectType; - float m_contactBreakingThreshold; - float m_contactProcessingThreshold; - int m_padding; - - btCollisionObjectFloatData *m_body0; - btCollisionObjectFloatData *m_body1; -}; - -#ifdef BT_USE_DOUBLE_PRECISION -#define btPersistentManifoldData btPersistentManifoldDoubleData -#define btPersistentManifoldDataName "btPersistentManifoldDoubleData" -#else -#define btPersistentManifoldData btPersistentManifoldFloatData -#define btPersistentManifoldDataName "btPersistentManifoldFloatData" -#endif //BT_USE_DOUBLE_PRECISION - +} +; diff --git a/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.cpp b/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.cpp index 08d6e6de8696..ec638f60ba53 100644 --- a/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.cpp +++ b/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.cpp @@ -72,18 +72,11 @@ bool btSubsimplexConvexCast::calcTimeOfImpact( btScalar dist2 = v.length2(); - #ifdef BT_USE_DOUBLE_PRECISION - btScalar epsilon = SIMD_EPSILON * 10; + btScalar epsilon = btScalar(0.0001); #else -//todo: epsilon kept for backward compatibility of unit tests. -//will need to digg deeper to make the algorithm more robust -//since, a large epsilon can cause an early termination with false -//positive results (ray intersections that shouldn't be there) btScalar epsilon = btScalar(0.0001); #endif //BT_USE_DOUBLE_PRECISION - - btVector3 w,p; btScalar VdotR; diff --git a/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.cpp b/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.cpp index 756373c9b5ee..23b4f79cfc20 100644 --- a/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.cpp +++ b/extern/bullet/src/BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.cpp @@ -190,9 +190,9 @@ bool btVoronoiSimplexSolver::updateClosestVectorAndPoints() const btVector3& c = m_simplexVectorW[2]; const btVector3& d = m_simplexVectorW[3]; - bool hasSeparation = closestPtPointTetrahedron(p,a,b,c,d,m_cachedBC); + bool hasSeperation = closestPtPointTetrahedron(p,a,b,c,d,m_cachedBC); - if (hasSeparation) + if (hasSeperation) { m_cachedP1 = m_simplexPointsP[0] * m_cachedBC.m_barycentricCoords[0] + diff --git a/extern/bullet/src/BulletCollision/premake4.lua b/extern/bullet/src/BulletCollision/premake4.lua index 6297bf3dfddf..70407771d8e7 100644 --- a/extern/bullet/src/BulletCollision/premake4.lua +++ b/extern/bullet/src/BulletCollision/premake4.lua @@ -1,9 +1,6 @@ project "BulletCollision" kind "StaticLib" - if os.is("Linux") then - buildoptions{"-fPIC"} - end includedirs { "..", } diff --git a/extern/bullet/src/BulletDynamics/CMakeLists.txt b/extern/bullet/src/BulletDynamics/CMakeLists.txt index d416d7d5f9eb..f8a6f34baf9a 100644 --- a/extern/bullet/src/BulletDynamics/CMakeLists.txt +++ b/extern/bullet/src/BulletDynamics/CMakeLists.txt @@ -15,8 +15,6 @@ SET(BulletDynamics_SRCS ConstraintSolver/btHingeConstraint.cpp ConstraintSolver/btPoint2PointConstraint.cpp ConstraintSolver/btSequentialImpulseConstraintSolver.cpp - ConstraintSolver/btSequentialImpulseConstraintSolverMt.cpp - ConstraintSolver/btBatchedConstraints.cpp ConstraintSolver/btNNCGConstraintSolver.cpp ConstraintSolver/btSliderConstraint.cpp ConstraintSolver/btSolve2LinearConstraint.cpp @@ -31,16 +29,15 @@ SET(BulletDynamics_SRCS Vehicle/btRaycastVehicle.cpp Vehicle/btWheelInfo.cpp Featherstone/btMultiBody.cpp - Featherstone/btMultiBodyConstraint.cpp Featherstone/btMultiBodyConstraintSolver.cpp Featherstone/btMultiBodyDynamicsWorld.cpp - Featherstone/btMultiBodyFixedConstraint.cpp - Featherstone/btMultiBodyGearConstraint.cpp Featherstone/btMultiBodyJointLimitConstraint.cpp - Featherstone/btMultiBodyJointMotor.cpp - Featherstone/btMultiBodyMLCPConstraintSolver.cpp + Featherstone/btMultiBodyConstraint.cpp Featherstone/btMultiBodyPoint2Point.cpp + Featherstone/btMultiBodyFixedConstraint.cpp Featherstone/btMultiBodySliderConstraint.cpp + Featherstone/btMultiBodyJointMotor.cpp + Featherstone/btMultiBodyGearConstraint.cpp MLCPSolvers/btDantzigLCP.cpp MLCPSolvers/btMLCPSolver.cpp MLCPSolvers/btLemkeAlgorithm.cpp @@ -65,7 +62,6 @@ SET(ConstraintSolver_HDRS ConstraintSolver/btJacobianEntry.h ConstraintSolver/btPoint2PointConstraint.h ConstraintSolver/btSequentialImpulseConstraintSolver.h - ConstraintSolver/btSequentialImpulseConstraintSolverMt.h ConstraintSolver/btNNCGConstraintSolver.h ConstraintSolver/btSliderConstraint.h ConstraintSolver/btSolve2LinearConstraint.h @@ -91,19 +87,19 @@ SET(Vehicle_HDRS SET(Featherstone_HDRS Featherstone/btMultiBody.h - Featherstone/btMultiBodyConstraint.h Featherstone/btMultiBodyConstraintSolver.h Featherstone/btMultiBodyDynamicsWorld.h - Featherstone/btMultiBodyFixedConstraint.h - Featherstone/btMultiBodyGearConstraint.h - Featherstone/btMultiBodyJointLimitConstraint.h - Featherstone/btMultiBodyJointMotor.h Featherstone/btMultiBodyLink.h Featherstone/btMultiBodyLinkCollider.h - Featherstone/btMultiBodyMLCPConstraintSolver.h + Featherstone/btMultiBodySolverConstraint.h + Featherstone/btMultiBodyConstraint.h + Featherstone/btMultiBodyJointLimitConstraint.h + Featherstone/btMultiBodyConstraint.h Featherstone/btMultiBodyPoint2Point.h + Featherstone/btMultiBodyFixedConstraint.h Featherstone/btMultiBodySliderConstraint.h - Featherstone/btMultiBodySolverConstraint.h + Featherstone/btMultiBodyJointMotor.h + Featherstone/btMultiBodyGearConstraint.h ) SET(MLCPSolvers_HDRS diff --git a/extern/bullet/src/BulletDynamics/Character/btCharacterControllerInterface.h b/extern/bullet/src/BulletDynamics/Character/btCharacterControllerInterface.h index abe24b5ca6cb..c3a3ac6c8ddf 100644 --- a/extern/bullet/src/BulletDynamics/Character/btCharacterControllerInterface.h +++ b/extern/bullet/src/BulletDynamics/Character/btCharacterControllerInterface.h @@ -37,7 +37,7 @@ class btCharacterControllerInterface : public btActionInterface virtual void preStep ( btCollisionWorld* collisionWorld) = 0; virtual void playerStep (btCollisionWorld* collisionWorld, btScalar dt) = 0; virtual bool canJump () const = 0; - virtual void jump(const btVector3& dir = btVector3(0, 0, 0)) = 0; + virtual void jump(const btVector3& dir = btVector3()) = 0; virtual bool onGround () const = 0; virtual void setUpInterpolate (bool value) = 0; diff --git a/extern/bullet/src/BulletDynamics/Character/btKinematicCharacterController.h b/extern/bullet/src/BulletDynamics/Character/btKinematicCharacterController.h index fe3cf2768b02..2dd12eaa5f10 100644 --- a/extern/bullet/src/BulletDynamics/Character/btKinematicCharacterController.h +++ b/extern/bullet/src/BulletDynamics/Character/btKinematicCharacterController.h @@ -176,7 +176,7 @@ ATTRIBUTE_ALIGNED16(class) btKinematicCharacterController : public btCharacterCo void setMaxJumpHeight (btScalar maxJumpHeight); bool canJump () const; - void jump(const btVector3& v = btVector3(0, 0, 0)); + void jump(const btVector3& v = btVector3()); void applyImpulse(const btVector3& v) { jump(v); } diff --git a/extern/bullet/src/BulletDynamics/ConstraintSolver/btBatchedConstraints.cpp b/extern/bullet/src/BulletDynamics/ConstraintSolver/btBatchedConstraints.cpp deleted file mode 100644 index c82ba87f9ff8..000000000000 --- a/extern/bullet/src/BulletDynamics/ConstraintSolver/btBatchedConstraints.cpp +++ /dev/null @@ -1,1128 +0,0 @@ -/* -Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - - -#include "btBatchedConstraints.h" - -#include "LinearMath/btIDebugDraw.h" -#include "LinearMath/btMinMax.h" -#include "LinearMath/btStackAlloc.h" -#include "LinearMath/btQuickprof.h" - -#include //for memset - -const int kNoMerge = -1; - -bool btBatchedConstraints::s_debugDrawBatches = false; - - -struct btBatchedConstraintInfo -{ - int constraintIndex; - int numConstraintRows; - int bodyIds[2]; -}; - - -struct btBatchInfo -{ - int numConstraints; - int mergeIndex; - - btBatchInfo() : numConstraints(0), mergeIndex(kNoMerge) {} -}; - - -bool btBatchedConstraints::validate(btConstraintArray* constraints, const btAlignedObjectArray& bodies) const -{ - // - // validate: for debugging only. Verify coloring of bodies, that no body is touched by more than one batch in any given phase - // - int errors = 0; - const int kUnassignedBatch = -1; - - btAlignedObjectArray bodyBatchId; - for (int iPhase = 0; iPhase < m_phases.size(); ++iPhase) - { - bodyBatchId.resizeNoInitialize(0); - bodyBatchId.resize( bodies.size(), kUnassignedBatch ); - const Range& phase = m_phases[iPhase]; - for (int iBatch = phase.begin; iBatch < phase.end; ++iBatch) - { - const Range& batch = m_batches[iBatch]; - for (int iiCons = batch.begin; iiCons < batch.end; ++iiCons) - { - int iCons = m_constraintIndices[iiCons]; - const btSolverConstraint& cons = constraints->at(iCons); - const btSolverBody& bodyA = bodies[cons.m_solverBodyIdA]; - const btSolverBody& bodyB = bodies[cons.m_solverBodyIdB]; - if (! bodyA.internalGetInvMass().isZero()) - { - int thisBodyBatchId = bodyBatchId[cons.m_solverBodyIdA]; - if (thisBodyBatchId == kUnassignedBatch) - { - bodyBatchId[cons.m_solverBodyIdA] = iBatch; - } - else if (thisBodyBatchId != iBatch) - { - btAssert( !"dynamic body is used in 2 different batches in the same phase" ); - errors++; - } - } - if (! bodyB.internalGetInvMass().isZero()) - { - int thisBodyBatchId = bodyBatchId[cons.m_solverBodyIdB]; - if (thisBodyBatchId == kUnassignedBatch) - { - bodyBatchId[cons.m_solverBodyIdB] = iBatch; - } - else if (thisBodyBatchId != iBatch) - { - btAssert( !"dynamic body is used in 2 different batches in the same phase" ); - errors++; - } - } - } - } - } - return errors == 0; -} - - -static void debugDrawSingleBatch( const btBatchedConstraints* bc, - btConstraintArray* constraints, - const btAlignedObjectArray& bodies, - int iBatch, - const btVector3& color, - const btVector3& offset - ) -{ - if (bc && bc->m_debugDrawer && iBatch < bc->m_batches.size()) - { - const btBatchedConstraints::Range& b = bc->m_batches[iBatch]; - for (int iiCon = b.begin; iiCon < b.end; ++iiCon) - { - int iCon = bc->m_constraintIndices[iiCon]; - const btSolverConstraint& con = constraints->at(iCon); - int iBody0 = con.m_solverBodyIdA; - int iBody1 = con.m_solverBodyIdB; - btVector3 pos0 = bodies[iBody0].getWorldTransform().getOrigin() + offset; - btVector3 pos1 = bodies[iBody1].getWorldTransform().getOrigin() + offset; - bc->m_debugDrawer->drawLine(pos0, pos1, color); - } - } -} - - -static void debugDrawPhase( const btBatchedConstraints* bc, - btConstraintArray* constraints, - const btAlignedObjectArray& bodies, - int iPhase, - const btVector3& color0, - const btVector3& color1, - const btVector3& offset - ) -{ - BT_PROFILE( "debugDrawPhase" ); - if ( bc && bc->m_debugDrawer && iPhase < bc->m_phases.size() ) - { - const btBatchedConstraints::Range& phase = bc->m_phases[iPhase]; - for (int iBatch = phase.begin; iBatch < phase.end; ++iBatch) - { - float tt = float(iBatch - phase.begin) / float(btMax(1, phase.end - phase.begin - 1)); - btVector3 col = lerp(color0, color1, tt); - debugDrawSingleBatch(bc, constraints, bodies, iBatch, col, offset); - } - } -} - - -static void debugDrawAllBatches( const btBatchedConstraints* bc, - btConstraintArray* constraints, - const btAlignedObjectArray& bodies - ) -{ - BT_PROFILE( "debugDrawAllBatches" ); - if ( bc && bc->m_debugDrawer && bc->m_phases.size() > 0 ) - { - btVector3 bboxMin(BT_LARGE_FLOAT, BT_LARGE_FLOAT, BT_LARGE_FLOAT); - btVector3 bboxMax = -bboxMin; - for (int iBody = 0; iBody < bodies.size(); ++iBody) - { - const btVector3& pos = bodies[iBody].getWorldTransform().getOrigin(); - bboxMin.setMin(pos); - bboxMax.setMax(pos); - } - btVector3 bboxExtent = bboxMax - bboxMin; - btVector3 offsetBase = btVector3( 0, bboxExtent.y()*1.1f, 0 ); - btVector3 offsetStep = btVector3( 0, 0, bboxExtent.z()*1.1f ); - int numPhases = bc->m_phases.size(); - for (int iPhase = 0; iPhase < numPhases; ++iPhase) - { - float b = float(iPhase)/float(numPhases-1); - btVector3 color0 = btVector3(1,0,b); - btVector3 color1 = btVector3(0,1,b); - btVector3 offset = offsetBase + offsetStep*(float(iPhase) - float(numPhases-1)*0.5); - debugDrawPhase(bc, constraints, bodies, iPhase, color0, color1, offset); - } - } -} - - -static void initBatchedBodyDynamicFlags(btAlignedObjectArray* outBodyDynamicFlags, const btAlignedObjectArray& bodies) -{ - BT_PROFILE("initBatchedBodyDynamicFlags"); - btAlignedObjectArray& bodyDynamicFlags = *outBodyDynamicFlags; - bodyDynamicFlags.resizeNoInitialize(bodies.size()); - for (int i = 0; i < bodies.size(); ++i) - { - const btSolverBody& body = bodies[ i ]; - bodyDynamicFlags[i] = ( body.internalGetInvMass().x() > btScalar( 0 ) ); - } -} - - -static int runLengthEncodeConstraintInfo(btBatchedConstraintInfo* outConInfos, int numConstraints) -{ - BT_PROFILE("runLengthEncodeConstraintInfo"); - // detect and run-length encode constraint rows that repeat the same bodies - int iDest = 0; - int iSrc = 0; - while (iSrc < numConstraints) - { - const btBatchedConstraintInfo& srcConInfo = outConInfos[iSrc]; - btBatchedConstraintInfo& conInfo = outConInfos[iDest]; - conInfo.constraintIndex = iSrc; - conInfo.bodyIds[0] = srcConInfo.bodyIds[0]; - conInfo.bodyIds[1] = srcConInfo.bodyIds[1]; - while (iSrc < numConstraints && outConInfos[iSrc].bodyIds[0] == srcConInfo.bodyIds[0] && outConInfos[iSrc].bodyIds[1] == srcConInfo.bodyIds[1]) - { - ++iSrc; - } - conInfo.numConstraintRows = iSrc - conInfo.constraintIndex; - ++iDest; - } - return iDest; -} - - -struct ReadSolverConstraintsLoop : public btIParallelForBody -{ - btBatchedConstraintInfo* m_outConInfos; - btConstraintArray* m_constraints; - - ReadSolverConstraintsLoop( btBatchedConstraintInfo* outConInfos, btConstraintArray* constraints ) - { - m_outConInfos = outConInfos; - m_constraints = constraints; - } - void forLoop( int iBegin, int iEnd ) const BT_OVERRIDE - { - for (int i = iBegin; i < iEnd; ++i) - { - btBatchedConstraintInfo& conInfo = m_outConInfos[i]; - const btSolverConstraint& con = m_constraints->at( i ); - conInfo.bodyIds[0] = con.m_solverBodyIdA; - conInfo.bodyIds[1] = con.m_solverBodyIdB; - conInfo.constraintIndex = i; - conInfo.numConstraintRows = 1; - } - } -}; - - -static int initBatchedConstraintInfo(btBatchedConstraintInfo* outConInfos, btConstraintArray* constraints) -{ - BT_PROFILE("initBatchedConstraintInfo"); - int numConstraints = constraints->size(); - bool inParallel = true; - if (inParallel) - { - ReadSolverConstraintsLoop loop(outConInfos, constraints); - int grainSize = 1200; - btParallelFor(0, numConstraints, grainSize, loop); - } - else - { - for (int i = 0; i < numConstraints; ++i) - { - btBatchedConstraintInfo& conInfo = outConInfos[i]; - const btSolverConstraint& con = constraints->at( i ); - conInfo.bodyIds[0] = con.m_solverBodyIdA; - conInfo.bodyIds[1] = con.m_solverBodyIdB; - conInfo.constraintIndex = i; - conInfo.numConstraintRows = 1; - } - } - bool useRunLengthEncoding = true; - if (useRunLengthEncoding) - { - numConstraints = runLengthEncodeConstraintInfo(outConInfos, numConstraints); - } - return numConstraints; -} - - -static void expandConstraintRowsInPlace(int* constraintBatchIds, const btBatchedConstraintInfo* conInfos, int numConstraints, int numConstraintRows) -{ - BT_PROFILE("expandConstraintRowsInPlace"); - if (numConstraintRows > numConstraints) - { - // we walk the array in reverse to avoid overwriteing - for (int iCon = numConstraints - 1; iCon >= 0; --iCon) - { - const btBatchedConstraintInfo& conInfo = conInfos[iCon]; - int iBatch = constraintBatchIds[iCon]; - for (int i = conInfo.numConstraintRows - 1; i >= 0; --i) - { - int iDest = conInfo.constraintIndex + i; - btAssert(iDest >= iCon); - btAssert(iDest >= 0 && iDest < numConstraintRows); - constraintBatchIds[iDest] = iBatch; - } - } - } -} - - -static void expandConstraintRows(int* destConstraintBatchIds, const int* srcConstraintBatchIds, const btBatchedConstraintInfo* conInfos, int numConstraints, int numConstraintRows) -{ - BT_PROFILE("expandConstraintRows"); - for ( int iCon = 0; iCon < numConstraints; ++iCon ) - { - const btBatchedConstraintInfo& conInfo = conInfos[ iCon ]; - int iBatch = srcConstraintBatchIds[ iCon ]; - for ( int i = 0; i < conInfo.numConstraintRows; ++i ) - { - int iDest = conInfo.constraintIndex + i; - btAssert( iDest >= iCon ); - btAssert( iDest >= 0 && iDest < numConstraintRows ); - destConstraintBatchIds[ iDest ] = iBatch; - } - } -} - - -struct ExpandConstraintRowsLoop : public btIParallelForBody -{ - int* m_destConstraintBatchIds; - const int* m_srcConstraintBatchIds; - const btBatchedConstraintInfo* m_conInfos; - int m_numConstraintRows; - - ExpandConstraintRowsLoop( int* destConstraintBatchIds, const int* srcConstraintBatchIds, const btBatchedConstraintInfo* conInfos, int numConstraintRows) - { - m_destConstraintBatchIds = destConstraintBatchIds; - m_srcConstraintBatchIds = srcConstraintBatchIds; - m_conInfos = conInfos; - m_numConstraintRows = numConstraintRows; - } - void forLoop( int iBegin, int iEnd ) const BT_OVERRIDE - { - expandConstraintRows(m_destConstraintBatchIds, m_srcConstraintBatchIds + iBegin, m_conInfos + iBegin, iEnd - iBegin, m_numConstraintRows); - } -}; - - -static void expandConstraintRowsMt(int* destConstraintBatchIds, const int* srcConstraintBatchIds, const btBatchedConstraintInfo* conInfos, int numConstraints, int numConstraintRows) -{ - BT_PROFILE("expandConstraintRowsMt"); - ExpandConstraintRowsLoop loop(destConstraintBatchIds, srcConstraintBatchIds, conInfos, numConstraintRows); - int grainSize = 600; - btParallelFor(0, numConstraints, grainSize, loop); -} - - -static void initBatchedConstraintInfoArray(btAlignedObjectArray* outConInfos, btConstraintArray* constraints) -{ - BT_PROFILE("initBatchedConstraintInfoArray"); - btAlignedObjectArray& conInfos = *outConInfos; - int numConstraints = constraints->size(); - conInfos.resizeNoInitialize(numConstraints); - - int newSize = initBatchedConstraintInfo(&outConInfos->at(0), constraints); - conInfos.resizeNoInitialize(newSize); -} - - -static void mergeSmallBatches(btBatchInfo* batches, int iBeginBatch, int iEndBatch, int minBatchSize, int maxBatchSize) -{ - BT_PROFILE("mergeSmallBatches"); - for ( int iBatch = iEndBatch - 1; iBatch >= iBeginBatch; --iBatch ) - { - btBatchInfo& batch = batches[ iBatch ]; - if ( batch.mergeIndex == kNoMerge && batch.numConstraints > 0 && batch.numConstraints < minBatchSize ) - { - for ( int iDestBatch = iBatch - 1; iDestBatch >= iBeginBatch; --iDestBatch ) - { - btBatchInfo& destBatch = batches[ iDestBatch ]; - if ( destBatch.mergeIndex == kNoMerge && ( destBatch.numConstraints + batch.numConstraints ) < maxBatchSize ) - { - destBatch.numConstraints += batch.numConstraints; - batch.numConstraints = 0; - batch.mergeIndex = iDestBatch; - break; - } - } - } - } - // flatten mergeIndexes - // e.g. in case where A was merged into B and then B was merged into C, we need A to point to C instead of B - // Note: loop goes forward through batches because batches always merge from higher indexes to lower, - // so by going from low to high it reduces the amount of trail-following - for ( int iBatch = iBeginBatch; iBatch < iEndBatch; ++iBatch ) - { - btBatchInfo& batch = batches[ iBatch ]; - if ( batch.mergeIndex != kNoMerge ) - { - int iMergeDest = batches[ batch.mergeIndex ].mergeIndex; - // follow trail of merges to the end - while ( iMergeDest != kNoMerge ) - { - int iNext = batches[ iMergeDest ].mergeIndex; - if ( iNext == kNoMerge ) - { - batch.mergeIndex = iMergeDest; - break; - } - iMergeDest = iNext; - } - } - } -} - - -static void updateConstraintBatchIdsForMerges(int* constraintBatchIds, int numConstraints, const btBatchInfo* batches, int numBatches) -{ - BT_PROFILE("updateConstraintBatchIdsForMerges"); - // update batchIds to account for merges - for (int i = 0; i < numConstraints; ++i) - { - int iBatch = constraintBatchIds[i]; - btAssert(iBatch < numBatches); - // if this constraint references a batch that was merged into another batch - if (batches[iBatch].mergeIndex != kNoMerge) - { - // update batchId - constraintBatchIds[i] = batches[iBatch].mergeIndex; - } - } -} - - -struct UpdateConstraintBatchIdsForMergesLoop : public btIParallelForBody -{ - int* m_constraintBatchIds; - const btBatchInfo* m_batches; - int m_numBatches; - - UpdateConstraintBatchIdsForMergesLoop( int* constraintBatchIds, const btBatchInfo* batches, int numBatches ) - { - m_constraintBatchIds = constraintBatchIds; - m_batches = batches; - m_numBatches = numBatches; - } - void forLoop( int iBegin, int iEnd ) const BT_OVERRIDE - { - BT_PROFILE( "UpdateConstraintBatchIdsForMergesLoop" ); - updateConstraintBatchIdsForMerges( m_constraintBatchIds + iBegin, iEnd - iBegin, m_batches, m_numBatches ); - } -}; - - -static void updateConstraintBatchIdsForMergesMt(int* constraintBatchIds, int numConstraints, const btBatchInfo* batches, int numBatches) -{ - BT_PROFILE( "updateConstraintBatchIdsForMergesMt" ); - UpdateConstraintBatchIdsForMergesLoop loop(constraintBatchIds, batches, numBatches); - int grainSize = 800; - btParallelFor(0, numConstraints, grainSize, loop); -} - - -inline bool BatchCompare(const btBatchedConstraints::Range& a, const btBatchedConstraints::Range& b) -{ - int lenA = a.end - a.begin; - int lenB = b.end - b.begin; - return lenA > lenB; -} - - -static void writeOutConstraintIndicesForRangeOfBatches(btBatchedConstraints* bc, - const int* constraintBatchIds, - int numConstraints, - int* constraintIdPerBatch, - int batchBegin, - int batchEnd - ) -{ - BT_PROFILE("writeOutConstraintIndicesForRangeOfBatches"); - for ( int iCon = 0; iCon < numConstraints; ++iCon ) - { - int iBatch = constraintBatchIds[ iCon ]; - if (iBatch >= batchBegin && iBatch < batchEnd) - { - int iDestCon = constraintIdPerBatch[ iBatch ]; - constraintIdPerBatch[ iBatch ] = iDestCon + 1; - bc->m_constraintIndices[ iDestCon ] = iCon; - } - } -} - - -struct WriteOutConstraintIndicesLoop : public btIParallelForBody -{ - btBatchedConstraints* m_batchedConstraints; - const int* m_constraintBatchIds; - int m_numConstraints; - int* m_constraintIdPerBatch; - int m_maxNumBatchesPerPhase; - - WriteOutConstraintIndicesLoop( btBatchedConstraints* bc, const int* constraintBatchIds, int numConstraints, int* constraintIdPerBatch, int maxNumBatchesPerPhase ) - { - m_batchedConstraints = bc; - m_constraintBatchIds = constraintBatchIds; - m_numConstraints = numConstraints; - m_constraintIdPerBatch = constraintIdPerBatch; - m_maxNumBatchesPerPhase = maxNumBatchesPerPhase; - } - void forLoop( int iBegin, int iEnd ) const BT_OVERRIDE - { - BT_PROFILE( "WriteOutConstraintIndicesLoop" ); - int batchBegin = iBegin * m_maxNumBatchesPerPhase; - int batchEnd = iEnd * m_maxNumBatchesPerPhase; - writeOutConstraintIndicesForRangeOfBatches(m_batchedConstraints, - m_constraintBatchIds, - m_numConstraints, - m_constraintIdPerBatch, - batchBegin, - batchEnd - ); - } -}; - - -static void writeOutConstraintIndicesMt(btBatchedConstraints* bc, - const int* constraintBatchIds, - int numConstraints, - int* constraintIdPerBatch, - int maxNumBatchesPerPhase, - int numPhases - ) -{ - BT_PROFILE("writeOutConstraintIndicesMt"); - bool inParallel = true; - if (inParallel) - { - WriteOutConstraintIndicesLoop loop( bc, constraintBatchIds, numConstraints, constraintIdPerBatch, maxNumBatchesPerPhase ); - btParallelFor( 0, numPhases, 1, loop ); - } - else - { - for ( int iCon = 0; iCon < numConstraints; ++iCon ) - { - int iBatch = constraintBatchIds[ iCon ]; - int iDestCon = constraintIdPerBatch[ iBatch ]; - constraintIdPerBatch[ iBatch ] = iDestCon + 1; - bc->m_constraintIndices[ iDestCon ] = iCon; - } - } -} - - -static void writeGrainSizes(btBatchedConstraints* bc) -{ - typedef btBatchedConstraints::Range Range; - int numPhases = bc->m_phases.size(); - bc->m_phaseGrainSize.resizeNoInitialize(numPhases); - int numThreads = btGetTaskScheduler()->getNumThreads(); - for (int iPhase = 0; iPhase < numPhases; ++iPhase) - { - const Range& phase = bc->m_phases[ iPhase ]; - int numBatches = phase.end - phase.begin; - float grainSize = floor((0.25f*numBatches / float(numThreads)) + 0.0f); - bc->m_phaseGrainSize[ iPhase ] = btMax(1, int(grainSize)); - } -} - - -static void writeOutBatches(btBatchedConstraints* bc, - const int* constraintBatchIds, - int numConstraints, - const btBatchInfo* batches, - int* batchWork, - int maxNumBatchesPerPhase, - int numPhases -) -{ - BT_PROFILE("writeOutBatches"); - typedef btBatchedConstraints::Range Range; - bc->m_constraintIndices.reserve( numConstraints ); - bc->m_batches.resizeNoInitialize( 0 ); - bc->m_phases.resizeNoInitialize( 0 ); - - //int maxNumBatches = numPhases * maxNumBatchesPerPhase; - { - int* constraintIdPerBatch = batchWork; // for each batch, keep an index into the next available slot in the m_constraintIndices array - int iConstraint = 0; - for (int iPhase = 0; iPhase < numPhases; ++iPhase) - { - int curPhaseBegin = bc->m_batches.size(); - int iBegin = iPhase * maxNumBatchesPerPhase; - int iEnd = iBegin + maxNumBatchesPerPhase; - for ( int i = iBegin; i < iEnd; ++i ) - { - const btBatchInfo& batch = batches[ i ]; - int curBatchBegin = iConstraint; - constraintIdPerBatch[ i ] = curBatchBegin; // record the start of each batch in m_constraintIndices array - int numConstraints = batch.numConstraints; - iConstraint += numConstraints; - if ( numConstraints > 0 ) - { - bc->m_batches.push_back( Range( curBatchBegin, iConstraint ) ); - } - } - // if any batches were emitted this phase, - if ( bc->m_batches.size() > curPhaseBegin ) - { - // output phase - bc->m_phases.push_back( Range( curPhaseBegin, bc->m_batches.size() ) ); - } - } - - btAssert(iConstraint == numConstraints); - bc->m_constraintIndices.resizeNoInitialize( numConstraints ); - writeOutConstraintIndicesMt( bc, constraintBatchIds, numConstraints, constraintIdPerBatch, maxNumBatchesPerPhase, numPhases ); - } - // for each phase - for (int iPhase = 0; iPhase < bc->m_phases.size(); ++iPhase) - { - // sort the batches from largest to smallest (can be helpful to some task schedulers) - const Range& curBatches = bc->m_phases[iPhase]; - bc->m_batches.quickSortInternal(BatchCompare, curBatches.begin, curBatches.end-1); - } - bc->m_phaseOrder.resize(bc->m_phases.size()); - for (int i = 0; i < bc->m_phases.size(); ++i) - { - bc->m_phaseOrder[i] = i; - } - writeGrainSizes(bc); -} - - -// -// PreallocatedMemoryHelper -- helper object for allocating a number of chunks of memory in a single contiguous block. -// It is generally more efficient to do a single larger allocation than many smaller allocations. -// -// Example Usage: -// -// btVector3* bodyPositions = NULL; -// btBatchedConstraintInfo* conInfos = NULL; -// { -// PreallocatedMemoryHelper<8> memHelper; -// memHelper.addChunk( (void**) &bodyPositions, sizeof( btVector3 ) * bodies.size() ); -// memHelper.addChunk( (void**) &conInfos, sizeof( btBatchedConstraintInfo ) * numConstraints ); -// void* memPtr = malloc( memHelper.getSizeToAllocate() ); // allocate the memory -// memHelper.setChunkPointers( memPtr ); // update pointers to chunks -// } -template -class PreallocatedMemoryHelper -{ - struct Chunk - { - void** ptr; - size_t size; - }; - Chunk m_chunks[N]; - int m_numChunks; -public: - PreallocatedMemoryHelper() {m_numChunks=0;} - void addChunk( void** ptr, size_t sz ) - { - btAssert( m_numChunks < N ); - if ( m_numChunks < N ) - { - Chunk& chunk = m_chunks[ m_numChunks ]; - chunk.ptr = ptr; - chunk.size = sz; - m_numChunks++; - } - } - size_t getSizeToAllocate() const - { - size_t totalSize = 0; - for (int i = 0; i < m_numChunks; ++i) - { - totalSize += m_chunks[i].size; - } - return totalSize; - } - void setChunkPointers(void* mem) const - { - size_t totalSize = 0; - for (int i = 0; i < m_numChunks; ++i) - { - const Chunk& chunk = m_chunks[ i ]; - char* chunkPtr = static_cast(mem) + totalSize; - *chunk.ptr = chunkPtr; - totalSize += chunk.size; - } - } -}; - - - -static btVector3 findMaxDynamicConstraintExtent( - btVector3* bodyPositions, - bool* bodyDynamicFlags, - btBatchedConstraintInfo* conInfos, - int numConstraints, - int numBodies - ) -{ - BT_PROFILE("findMaxDynamicConstraintExtent"); - btVector3 consExtent = btVector3(1,1,1) * 0.001; - for (int iCon = 0; iCon < numConstraints; ++iCon) - { - const btBatchedConstraintInfo& con = conInfos[ iCon ]; - int iBody0 = con.bodyIds[0]; - int iBody1 = con.bodyIds[1]; - btAssert(iBody0 >= 0 && iBody0 < numBodies); - btAssert(iBody1 >= 0 && iBody1 < numBodies); - // is it a dynamic constraint? - if (bodyDynamicFlags[iBody0] && bodyDynamicFlags[iBody1]) - { - btVector3 delta = bodyPositions[iBody1] - bodyPositions[iBody0]; - consExtent.setMax(delta.absolute()); - } - } - return consExtent; -} - - -struct btIntVec3 -{ - int m_ints[ 3 ]; - - SIMD_FORCE_INLINE const int& operator[](int i) const {return m_ints[i];} - SIMD_FORCE_INLINE int& operator[](int i) {return m_ints[i];} -}; - - -struct AssignConstraintsToGridBatchesParams -{ - bool* bodyDynamicFlags; - btIntVec3* bodyGridCoords; - int numBodies; - btBatchedConstraintInfo* conInfos; - int* constraintBatchIds; - btIntVec3 gridChunkDim; - int maxNumBatchesPerPhase; - int numPhases; - int phaseMask; - - AssignConstraintsToGridBatchesParams() - { - memset(this, 0, sizeof(*this)); - } -}; - - -static void assignConstraintsToGridBatches(const AssignConstraintsToGridBatchesParams& params, int iConBegin, int iConEnd) -{ - BT_PROFILE("assignConstraintsToGridBatches"); - // (can be done in parallel) - for ( int iCon = iConBegin; iCon < iConEnd; ++iCon ) - { - const btBatchedConstraintInfo& con = params.conInfos[ iCon ]; - int iBody0 = con.bodyIds[ 0 ]; - int iBody1 = con.bodyIds[ 1 ]; - int iPhase = iCon; //iBody0; // pseudorandom choice to distribute evenly amongst phases - iPhase &= params.phaseMask; - int gridCoord[ 3 ]; - // is it a dynamic constraint? - if ( params.bodyDynamicFlags[ iBody0 ] && params.bodyDynamicFlags[ iBody1 ] ) - { - const btIntVec3& body0Coords = params.bodyGridCoords[iBody0]; - const btIntVec3& body1Coords = params.bodyGridCoords[iBody1]; - // for each dimension x,y,z, - for (int i = 0; i < 3; ++i) - { - int coordMin = btMin(body0Coords.m_ints[i], body1Coords.m_ints[i]); - int coordMax = btMax(body0Coords.m_ints[i], body1Coords.m_ints[i]); - if (coordMin != coordMax) - { - btAssert( coordMax == coordMin + 1 ); - if ((coordMin&1) == 0) - { - iPhase &= ~(1 << i); // force bit off - } - else - { - iPhase |= (1 << i); // force bit on - iPhase &= params.phaseMask; - } - } - gridCoord[ i ] = coordMin; - } - } - else - { - if ( !params.bodyDynamicFlags[ iBody0 ] ) - { - iBody0 = con.bodyIds[ 1 ]; - } - btAssert(params.bodyDynamicFlags[ iBody0 ]); - const btIntVec3& body0Coords = params.bodyGridCoords[iBody0]; - // for each dimension x,y,z, - for ( int i = 0; i < 3; ++i ) - { - gridCoord[ i ] = body0Coords.m_ints[ i ]; - } - } - // calculate chunk coordinates - int chunkCoord[ 3 ]; - btIntVec3 gridChunkDim = params.gridChunkDim; - // for each dimension x,y,z, - for ( int i = 0; i < 3; ++i ) - { - int coordOffset = ( iPhase >> i ) & 1; - chunkCoord[ i ] = (gridCoord[ i ] - coordOffset)/2; - btClamp( chunkCoord[ i ], 0, gridChunkDim[ i ] - 1); - btAssert( chunkCoord[ i ] < gridChunkDim[ i ] ); - } - int iBatch = iPhase * params.maxNumBatchesPerPhase + chunkCoord[ 0 ] + chunkCoord[ 1 ] * gridChunkDim[ 0 ] + chunkCoord[ 2 ] * gridChunkDim[ 0 ] * gridChunkDim[ 1 ]; - btAssert(iBatch >= 0 && iBatch < params.maxNumBatchesPerPhase*params.numPhases); - params.constraintBatchIds[ iCon ] = iBatch; - } -} - - -struct AssignConstraintsToGridBatchesLoop : public btIParallelForBody -{ - const AssignConstraintsToGridBatchesParams* m_params; - - AssignConstraintsToGridBatchesLoop( const AssignConstraintsToGridBatchesParams& params ) - { - m_params = ¶ms; - } - void forLoop( int iBegin, int iEnd ) const BT_OVERRIDE - { - assignConstraintsToGridBatches(*m_params, iBegin, iEnd); - } -}; - - -// -// setupSpatialGridBatchesMt -- generate batches using a uniform 3D grid -// -/* - -Bodies are treated as 3D points at their center of mass. We only consider dynamic bodies at this stage, -because only dynamic bodies are mutated when a constraint is solved, thus subject to race conditions. - -1. Compute a bounding box around all dynamic bodies -2. Compute the maximum extent of all dynamic constraints. Each dynamic constraint is treated as a line segment, and we need the size of - box that will fully enclose any single dynamic constraint - -3. Establish the cell size of our grid, the cell size in each dimension must be at least as large as the dynamic constraints max-extent, - so that no dynamic constraint can span more than 2 cells of our grid on any axis of the grid. The cell size should be adjusted - larger in order to keep the total number of cells from being excessively high - -Key idea: Given that each constraint spans 1 or 2 grid cells in each dimension, we can handle all constraints by processing - in chunks of 2x2x2 cells with 8 different 1-cell offsets ((0,0,0),(0,0,1),(0,1,0),(0,1,1),(1,0,0)...). - For each of the 8 offsets, we create a phase, and for each 2x2x2 chunk with dynamic constraints becomes a batch in that phase. - -4. Once the grid is established, we can calculate for each constraint which phase and batch it belongs in. - -5. Do a merge small batches on the batches of each phase separately, to try to even out the sizes of batches - -Optionally, we can "collapse" one dimension of our 3D grid to turn it into a 2D grid, which reduces the number of phases -to 4. With fewer phases, there are more constraints per phase and this makes it easier to create batches of a useful size. -*/ -// -static void setupSpatialGridBatchesMt( - btBatchedConstraints* batchedConstraints, - btAlignedObjectArray* scratchMemory, - btConstraintArray* constraints, - const btAlignedObjectArray& bodies, - int minBatchSize, - int maxBatchSize, - bool use2DGrid -) -{ - BT_PROFILE("setupSpatialGridBatchesMt"); - const int numPhases = 8; - int numConstraints = constraints->size(); - int numConstraintRows = constraints->size(); - - const int maxGridChunkCount = 128; - int allocNumBatchesPerPhase = maxGridChunkCount; - int minNumBatchesPerPhase = 16; - int allocNumBatches = allocNumBatchesPerPhase * numPhases; - - btVector3* bodyPositions = NULL; - bool* bodyDynamicFlags = NULL; - btIntVec3* bodyGridCoords = NULL; - btBatchInfo* batches = NULL; - int* batchWork = NULL; - btBatchedConstraintInfo* conInfos = NULL; - int* constraintBatchIds = NULL; - int* constraintRowBatchIds = NULL; - { - PreallocatedMemoryHelper<10> memHelper; - memHelper.addChunk( (void**) &bodyPositions, sizeof( btVector3 ) * bodies.size() ); - memHelper.addChunk( (void**) &bodyDynamicFlags, sizeof( bool ) * bodies.size() ); - memHelper.addChunk( (void**) &bodyGridCoords, sizeof( btIntVec3 ) * bodies.size() ); - memHelper.addChunk( (void**) &batches, sizeof( btBatchInfo )* allocNumBatches ); - memHelper.addChunk( (void**) &batchWork, sizeof( int )* allocNumBatches ); - memHelper.addChunk( (void**) &conInfos, sizeof( btBatchedConstraintInfo ) * numConstraints ); - memHelper.addChunk( (void**) &constraintBatchIds, sizeof( int ) * numConstraints ); - memHelper.addChunk( (void**) &constraintRowBatchIds, sizeof( int ) * numConstraintRows ); - size_t scratchSize = memHelper.getSizeToAllocate(); - // if we need to reallocate - if (scratchMemory->capacity() < scratchSize) - { - // allocate 6.25% extra to avoid repeated reallocs - scratchMemory->reserve( scratchSize + scratchSize/16 ); - } - scratchMemory->resizeNoInitialize( scratchSize ); - char* memPtr = &scratchMemory->at(0); - memHelper.setChunkPointers( memPtr ); - } - - numConstraints = initBatchedConstraintInfo(conInfos, constraints); - - // compute bounding box around all dynamic bodies - // (could be done in parallel) - btVector3 bboxMin(BT_LARGE_FLOAT, BT_LARGE_FLOAT, BT_LARGE_FLOAT); - btVector3 bboxMax = -bboxMin; - //int dynamicBodyCount = 0; - for (int i = 0; i < bodies.size(); ++i) - { - const btSolverBody& body = bodies[i]; - btVector3 bodyPos = body.getWorldTransform().getOrigin(); - bool isDynamic = ( body.internalGetInvMass().x() > btScalar( 0 ) ); - bodyPositions[i] = bodyPos; - bodyDynamicFlags[i] = isDynamic; - if (isDynamic) - { - //dynamicBodyCount++; - bboxMin.setMin(bodyPos); - bboxMax.setMax(bodyPos); - } - } - - // find max extent of all dynamic constraints - // (could be done in parallel) - btVector3 consExtent = findMaxDynamicConstraintExtent(bodyPositions, bodyDynamicFlags, conInfos, numConstraints, bodies.size()); - - btVector3 gridExtent = bboxMax - bboxMin; - - btVector3 gridCellSize = consExtent; - int gridDim[3]; - gridDim[ 0 ] = int( 1.0 + gridExtent.x() / gridCellSize.x() ); - gridDim[ 1 ] = int( 1.0 + gridExtent.y() / gridCellSize.y() ); - gridDim[ 2 ] = int( 1.0 + gridExtent.z() / gridCellSize.z() ); - - // if we can collapse an axis, it will cut our number of phases in half which could be more efficient - int phaseMask = 7; - bool collapseAxis = use2DGrid; - if ( collapseAxis ) - { - // pick the smallest axis to collapse, leaving us with the greatest number of cells in our grid - int iAxisToCollapse = 0; - int axisDim = gridDim[iAxisToCollapse]; - //for each dimension - for ( int i = 0; i < 3; ++i ) - { - if (gridDim[i] < axisDim) - { - iAxisToCollapse = i; - axisDim = gridDim[i]; - } - } - // collapse it - gridCellSize[iAxisToCollapse] = gridExtent[iAxisToCollapse] * 2.0f; - phaseMask &= ~(1 << iAxisToCollapse); - } - - int numGridChunks = 0; - btIntVec3 gridChunkDim; // each chunk is 2x2x2 group of cells - while (true) - { - gridDim[0] = int( 1.0 + gridExtent.x() / gridCellSize.x() ); - gridDim[1] = int( 1.0 + gridExtent.y() / gridCellSize.y() ); - gridDim[2] = int( 1.0 + gridExtent.z() / gridCellSize.z() ); - gridChunkDim[ 0 ] = btMax( 1, ( gridDim[ 0 ] + 0 ) / 2 ); - gridChunkDim[ 1 ] = btMax( 1, ( gridDim[ 1 ] + 0 ) / 2 ); - gridChunkDim[ 2 ] = btMax( 1, ( gridDim[ 2 ] + 0 ) / 2 ); - numGridChunks = gridChunkDim[ 0 ] * gridChunkDim[ 1 ] * gridChunkDim[ 2 ]; - float nChunks = float(gridChunkDim[0]) * float(gridChunkDim[1]) * float(gridChunkDim[2]); // suceptible to integer overflow - if ( numGridChunks <= maxGridChunkCount && nChunks <= maxGridChunkCount ) - { - break; - } - gridCellSize *= 1.25; // should roughly cut numCells in half - } - btAssert(numGridChunks <= maxGridChunkCount ); - int maxNumBatchesPerPhase = numGridChunks; - - // for each dynamic body, compute grid coords - btVector3 invGridCellSize = btVector3(1,1,1)/gridCellSize; - // (can be done in parallel) - for (int iBody = 0; iBody < bodies.size(); ++iBody) - { - btIntVec3& coords = bodyGridCoords[iBody]; - if (bodyDynamicFlags[iBody]) - { - btVector3 v = ( bodyPositions[ iBody ] - bboxMin )*invGridCellSize; - coords.m_ints[0] = int(v.x()); - coords.m_ints[1] = int(v.y()); - coords.m_ints[2] = int(v.z()); - btAssert(coords.m_ints[0] >= 0 && coords.m_ints[0] < gridDim[0]); - btAssert(coords.m_ints[1] >= 0 && coords.m_ints[1] < gridDim[1]); - btAssert(coords.m_ints[2] >= 0 && coords.m_ints[2] < gridDim[2]); - } - else - { - coords.m_ints[0] = -1; - coords.m_ints[1] = -1; - coords.m_ints[2] = -1; - } - } - - for (int iPhase = 0; iPhase < numPhases; ++iPhase) - { - int batchBegin = iPhase * maxNumBatchesPerPhase; - int batchEnd = batchBegin + maxNumBatchesPerPhase; - for ( int iBatch = batchBegin; iBatch < batchEnd; ++iBatch ) - { - btBatchInfo& batch = batches[ iBatch ]; - batch = btBatchInfo(); - } - } - - { - AssignConstraintsToGridBatchesParams params; - params.bodyDynamicFlags = bodyDynamicFlags; - params.bodyGridCoords = bodyGridCoords; - params.numBodies = bodies.size(); - params.conInfos = conInfos; - params.constraintBatchIds = constraintBatchIds; - params.gridChunkDim = gridChunkDim; - params.maxNumBatchesPerPhase = maxNumBatchesPerPhase; - params.numPhases = numPhases; - params.phaseMask = phaseMask; - bool inParallel = true; - if (inParallel) - { - AssignConstraintsToGridBatchesLoop loop(params); - int grainSize = 250; - btParallelFor(0, numConstraints, grainSize, loop); - } - else - { - assignConstraintsToGridBatches( params, 0, numConstraints ); - } - } - for ( int iCon = 0; iCon < numConstraints; ++iCon ) - { - const btBatchedConstraintInfo& con = conInfos[ iCon ]; - int iBatch = constraintBatchIds[ iCon ]; - btBatchInfo& batch = batches[iBatch]; - batch.numConstraints += con.numConstraintRows; - } - - for (int iPhase = 0; iPhase < numPhases; ++iPhase) - { - // if phase is legit, - if (iPhase == (iPhase&phaseMask)) - { - int iBeginBatch = iPhase * maxNumBatchesPerPhase; - int iEndBatch = iBeginBatch + maxNumBatchesPerPhase; - mergeSmallBatches( batches, iBeginBatch, iEndBatch, minBatchSize, maxBatchSize ); - } - } - // all constraints have been assigned a batchId - updateConstraintBatchIdsForMergesMt(constraintBatchIds, numConstraints, batches, maxNumBatchesPerPhase*numPhases); - - if (numConstraintRows > numConstraints) - { - expandConstraintRowsMt(&constraintRowBatchIds[0], &constraintBatchIds[0], &conInfos[0], numConstraints, numConstraintRows); - } - else - { - constraintRowBatchIds = constraintBatchIds; - } - - writeOutBatches(batchedConstraints, constraintRowBatchIds, numConstraintRows, batches, batchWork, maxNumBatchesPerPhase, numPhases); - btAssert(batchedConstraints->validate(constraints, bodies)); -} - - -static void setupSingleBatch( - btBatchedConstraints* bc, - int numConstraints -) -{ - BT_PROFILE("setupSingleBatch"); - typedef btBatchedConstraints::Range Range; - - bc->m_constraintIndices.resize( numConstraints ); - for ( int i = 0; i < numConstraints; ++i ) - { - bc->m_constraintIndices[ i ] = i; - } - - bc->m_batches.resizeNoInitialize( 0 ); - bc->m_phases.resizeNoInitialize( 0 ); - bc->m_phaseOrder.resizeNoInitialize( 0 ); - bc->m_phaseGrainSize.resizeNoInitialize( 0 ); - - if (numConstraints > 0) - { - bc->m_batches.push_back( Range( 0, numConstraints ) ); - bc->m_phases.push_back( Range( 0, 1 ) ); - bc->m_phaseOrder.push_back(0); - bc->m_phaseGrainSize.push_back(1); - } -} - - -void btBatchedConstraints::setup( - btConstraintArray* constraints, - const btAlignedObjectArray& bodies, - BatchingMethod batchingMethod, - int minBatchSize, - int maxBatchSize, - btAlignedObjectArray* scratchMemory - ) -{ - if (constraints->size() >= minBatchSize*4) - { - bool use2DGrid = batchingMethod == BATCHING_METHOD_SPATIAL_GRID_2D; - setupSpatialGridBatchesMt( this, scratchMemory, constraints, bodies, minBatchSize, maxBatchSize, use2DGrid ); - if (s_debugDrawBatches) - { - debugDrawAllBatches( this, constraints, bodies ); - } - } - else - { - setupSingleBatch( this, constraints->size() ); - } -} - - diff --git a/extern/bullet/src/BulletDynamics/ConstraintSolver/btBatchedConstraints.h b/extern/bullet/src/BulletDynamics/ConstraintSolver/btBatchedConstraints.h deleted file mode 100644 index 0fd8f31dd453..000000000000 --- a/extern/bullet/src/BulletDynamics/ConstraintSolver/btBatchedConstraints.h +++ /dev/null @@ -1,66 +0,0 @@ -/* -Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#ifndef BT_BATCHED_CONSTRAINTS_H -#define BT_BATCHED_CONSTRAINTS_H - -#include "LinearMath/btThreads.h" -#include "LinearMath/btAlignedObjectArray.h" -#include "BulletDynamics/ConstraintSolver/btSolverBody.h" -#include "BulletDynamics/ConstraintSolver/btSolverConstraint.h" - - -class btIDebugDraw; - -struct btBatchedConstraints -{ - enum BatchingMethod - { - BATCHING_METHOD_SPATIAL_GRID_2D, - BATCHING_METHOD_SPATIAL_GRID_3D, - BATCHING_METHOD_COUNT - }; - struct Range - { - int begin; - int end; - - Range() : begin( 0 ), end( 0 ) {} - Range( int _beg, int _end ) : begin( _beg ), end( _end ) {} - }; - - btAlignedObjectArray m_constraintIndices; - btAlignedObjectArray m_batches; // each batch is a range of indices in the m_constraintIndices array - btAlignedObjectArray m_phases; // each phase is range of indices in the m_batches array - btAlignedObjectArray m_phaseGrainSize; // max grain size for each phase - btAlignedObjectArray m_phaseOrder; // phases can be done in any order, so we can randomize the order here - btIDebugDraw* m_debugDrawer; - - static bool s_debugDrawBatches; - - btBatchedConstraints() {m_debugDrawer=NULL;} - void setup( btConstraintArray* constraints, - const btAlignedObjectArray& bodies, - BatchingMethod batchingMethod, - int minBatchSize, - int maxBatchSize, - btAlignedObjectArray* scratchMemory - ); - bool validate( btConstraintArray* constraints, const btAlignedObjectArray& bodies ) const; -}; - - -#endif // BT_BATCHED_CONSTRAINTS_H - diff --git a/extern/bullet/src/BulletDynamics/ConstraintSolver/btContactSolverInfo.h b/extern/bullet/src/BulletDynamics/ConstraintSolver/btContactSolverInfo.h index 93865cbc5920..28d0c1dd4836 100644 --- a/extern/bullet/src/BulletDynamics/ConstraintSolver/btContactSolverInfo.h +++ b/extern/bullet/src/BulletDynamics/ConstraintSolver/btContactSolverInfo.h @@ -29,8 +29,7 @@ enum btSolverMode SOLVER_CACHE_FRIENDLY = 128, SOLVER_SIMD = 256, SOLVER_INTERLEAVE_CONTACT_AND_FRICTION_CONSTRAINTS = 512, - SOLVER_ALLOW_ZERO_LENGTH_FRICTION_DIRECTIONS = 1024, - SOLVER_DISABLE_IMPLICIT_CONE_FRICTION = 2048 + SOLVER_ALLOW_ZERO_LENGTH_FRICTION_DIRECTIONS = 1024 }; struct btContactSolverInfoData diff --git a/extern/bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.cpp b/extern/bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.cpp index c38b8353f068..fa17254ec3f2 100644 --- a/extern/bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.cpp +++ b/extern/bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.cpp @@ -855,8 +855,8 @@ int btGeneric6DofConstraint::get_limit_motor_info2( tag_vel, info->fps * limot->m_stopERP); info->m_constraintError[srow] += mot_fact * limot->m_targetVelocity; - info->m_lowerLimit[srow] = -limot->m_maxMotorForce / info->fps; - info->m_upperLimit[srow] = limot->m_maxMotorForce / info->fps; + info->m_lowerLimit[srow] = -limot->m_maxMotorForce; + info->m_upperLimit[srow] = limot->m_maxMotorForce; } } if(limit) diff --git a/extern/bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.h b/extern/bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.h index b2ad45f749de..bea8629c3259 100644 --- a/extern/bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.h +++ b/extern/bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.h @@ -77,7 +77,7 @@ class btRotationalLimitMotor { m_accumulatedImpulse = 0.f; m_targetVelocity = 0; - m_maxMotorForce = 6.0f; + m_maxMotorForce = 0.1f; m_maxLimitForce = 300.0f; m_loLimit = 1.0f; m_hiLimit = -1.0f; diff --git a/extern/bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.cpp b/extern/bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.cpp index 611b3034264b..e2d3a69839bb 100644 --- a/extern/bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.cpp +++ b/extern/bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.cpp @@ -719,8 +719,8 @@ int btGeneric6DofSpring2Constraint::get_limit_motor_info2( tag_vel, info->fps * limot->m_motorERP); info->m_constraintError[srow] = mot_fact * limot->m_targetVelocity; - info->m_lowerLimit[srow] = -limot->m_maxMotorForce / info->fps; - info->m_upperLimit[srow] = limot->m_maxMotorForce / info->fps; + info->m_lowerLimit[srow] = -limot->m_maxMotorForce; + info->m_upperLimit[srow] = limot->m_maxMotorForce; info->cfm[srow] = limot->m_motorCFM; srow += info->rowskip; ++count; @@ -769,8 +769,8 @@ int btGeneric6DofSpring2Constraint::get_limit_motor_info2( mot_fact = 0; } info->m_constraintError[srow] = mot_fact * targetvelocity * (rotational ? -1 : 1); - info->m_lowerLimit[srow] = -limot->m_maxMotorForce / info->fps; - info->m_upperLimit[srow] = limot->m_maxMotorForce / info->fps; + info->m_lowerLimit[srow] = -limot->m_maxMotorForce; + info->m_upperLimit[srow] = limot->m_maxMotorForce; info->cfm[srow] = limot->m_motorCFM; srow += info->rowskip; ++count; @@ -797,12 +797,6 @@ int btGeneric6DofSpring2Constraint::get_limit_motor_info2( btScalar cfm = BT_ZERO; btScalar mA = BT_ONE / m_rbA.getInvMass(); btScalar mB = BT_ONE / m_rbB.getInvMass(); - if (rotational) { - btScalar rrA = (m_calculatedTransformA.getOrigin() - transA.getOrigin()).length2(); - btScalar rrB = (m_calculatedTransformB.getOrigin() - transB.getOrigin()).length2(); - if (m_rbA.getInvMass()) mA = mA * rrA + 1 / (m_rbA.getInvInertiaTensorWorld() * ax1).length(); - if (m_rbB.getInvMass()) mB = mB * rrB + 1 / (m_rbB.getInvInertiaTensorWorld() * ax1).length(); - } btScalar m = mA > mB ? mB : mA; btScalar angularfreq = sqrt(ks / m); @@ -821,18 +815,7 @@ int btGeneric6DofSpring2Constraint::get_limit_motor_info2( btScalar fd = -kd * (vel) * (rotational ? -1 : 1) * dt; btScalar f = (fs+fd); - // after the spring force affecting the body(es) the new velocity will be - // vel + f / m * (rotational ? -1 : 1) - // so in theory this should be set here for m_constraintError - // (with m_constraintError we set a desired velocity for the affected body(es)) - // however in practice any value is fine as long as it is greater then the "proper" velocity, - // because the m_lowerLimit and the m_upperLimit will determinate the strength of the final pulling force - // so it is much simpler (and more robust) just to simply use inf (with the proper sign) - // you may also wonder what if the current velocity (vel) so high that the pulling force will not change its direction (in this iteration) - // will we not request a velocity with the wrong direction ? - // and the answare is not, because in practice during the solving the current velocity is subtracted from the m_constraintError - // so the sign of the force that is really matters - info->m_constraintError[srow] = (rotational ? -1 : 1) * (f < 0 ? -SIMD_INFINITY : SIMD_INFINITY); + info->m_constraintError[srow] = (vel + f * (rotational ? -1 : 1)) ; btScalar minf = f < fd ? f : fd; btScalar maxf = f < fd ? fd : f; diff --git a/extern/bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.h b/extern/bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.h index fc2ed4f7a989..536e5af1b9c4 100644 --- a/extern/bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.h +++ b/extern/bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.h @@ -107,7 +107,7 @@ class btRotationalLimitMotor2 m_motorCFM = 0.f; m_enableMotor = false; m_targetVelocity = 0; - m_maxMotorForce = 6.0f; + m_maxMotorForce = 0.1f; m_servoMotor = false; m_servoTarget = 0; m_enableSpring = false; diff --git a/extern/bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpringConstraint.cpp b/extern/bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpringConstraint.cpp index 3f875989ea52..6f765884ec0a 100644 --- a/extern/bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpringConstraint.cpp +++ b/extern/bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpringConstraint.cpp @@ -131,7 +131,7 @@ void btGeneric6DofSpringConstraint::internalUpdateSprings(btConstraintInfo2* inf btScalar force = delta * m_springStiffness[i]; btScalar velFactor = info->fps * m_springDamping[i] / btScalar(info->m_numIterations); m_linearLimits.m_targetVelocity[i] = velFactor * force; - m_linearLimits.m_maxMotorForce[i] = btFabs(force); + m_linearLimits.m_maxMotorForce[i] = btFabs(force) / info->fps; } } for(i = 0; i < 3; i++) @@ -146,7 +146,7 @@ void btGeneric6DofSpringConstraint::internalUpdateSprings(btConstraintInfo2* inf btScalar force = -delta * m_springStiffness[i+3]; btScalar velFactor = info->fps * m_springDamping[i+3] / btScalar(info->m_numIterations); m_angularLimits[i].m_targetVelocity = velFactor * force; - m_angularLimits[i].m_maxMotorForce = btFabs(force); + m_angularLimits[i].m_maxMotorForce = btFabs(force) / info->fps; } } } diff --git a/extern/bullet/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp b/extern/bullet/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp index 4df7b33adb84..b0d57a3e870a 100644 --- a/extern/bullet/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp +++ b/extern/bullet/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp @@ -21,7 +21,6 @@ subject to the following restrictions: #include "btSequentialImpulseConstraintSolver.h" #include "BulletCollision/NarrowPhaseCollision/btPersistentManifold.h" - #include "LinearMath/btIDebugDraw.h" #include "LinearMath/btCpuFeatureUtility.h" @@ -43,11 +42,11 @@ int gNumSplitImpulseRecoveries = 0; //#define VERBOSE_RESIDUAL_PRINTF 1 ///This is the scalar reference implementation of solving a single constraint row, the innerloop of the Projected Gauss Seidel/Sequential Impulse constraint solver ///Below are optional SSE2 and SSE4/FMA3 versions. We assume most hardware has SSE2. For SSE4/FMA3 we perform a CPU feature check. -static btScalar gResolveSingleConstraintRowGeneric_scalar_reference(btSolverBody& bodyA, btSolverBody& bodyB, const btSolverConstraint& c) +static btSimdScalar gResolveSingleConstraintRowGeneric_scalar_reference(btSolverBody& body1, btSolverBody& body2, const btSolverConstraint& c) { btScalar deltaImpulse = c.m_rhs - btScalar(c.m_appliedImpulse)*c.m_cfm; - const btScalar deltaVel1Dotn = c.m_contactNormal1.dot(bodyA.internalGetDeltaLinearVelocity()) + c.m_relpos1CrossNormal.dot(bodyA.internalGetDeltaAngularVelocity()); - const btScalar deltaVel2Dotn = c.m_contactNormal2.dot(bodyB.internalGetDeltaLinearVelocity()) + c.m_relpos2CrossNormal.dot(bodyB.internalGetDeltaAngularVelocity()); + const btScalar deltaVel1Dotn = c.m_contactNormal1.dot(body1.internalGetDeltaLinearVelocity()) + c.m_relpos1CrossNormal.dot(body1.internalGetDeltaAngularVelocity()); + const btScalar deltaVel2Dotn = c.m_contactNormal2.dot(body2.internalGetDeltaLinearVelocity()) + c.m_relpos2CrossNormal.dot(body2.internalGetDeltaAngularVelocity()); // const btScalar delta_rel_vel = deltaVel1Dotn-deltaVel2Dotn; deltaImpulse -= deltaVel1Dotn*c.m_jacDiagABInv; @@ -69,18 +68,18 @@ static btScalar gResolveSingleConstraintRowGeneric_scalar_reference(btSolverBody c.m_appliedImpulse = sum; } - bodyA.internalApplyImpulse(c.m_contactNormal1*bodyA.internalGetInvMass(), c.m_angularComponentA, deltaImpulse); - bodyB.internalApplyImpulse(c.m_contactNormal2*bodyB.internalGetInvMass(), c.m_angularComponentB, deltaImpulse); + body1.internalApplyImpulse(c.m_contactNormal1*body1.internalGetInvMass(), c.m_angularComponentA, deltaImpulse); + body2.internalApplyImpulse(c.m_contactNormal2*body2.internalGetInvMass(), c.m_angularComponentB, deltaImpulse); - return deltaImpulse*(1./c.m_jacDiagABInv); + return deltaImpulse; } -static btScalar gResolveSingleConstraintRowLowerLimit_scalar_reference(btSolverBody& bodyA, btSolverBody& bodyB, const btSolverConstraint& c) +static btSimdScalar gResolveSingleConstraintRowLowerLimit_scalar_reference(btSolverBody& body1, btSolverBody& body2, const btSolverConstraint& c) { btScalar deltaImpulse = c.m_rhs - btScalar(c.m_appliedImpulse)*c.m_cfm; - const btScalar deltaVel1Dotn = c.m_contactNormal1.dot(bodyA.internalGetDeltaLinearVelocity()) + c.m_relpos1CrossNormal.dot(bodyA.internalGetDeltaAngularVelocity()); - const btScalar deltaVel2Dotn = c.m_contactNormal2.dot(bodyB.internalGetDeltaLinearVelocity()) + c.m_relpos2CrossNormal.dot(bodyB.internalGetDeltaAngularVelocity()); + const btScalar deltaVel1Dotn = c.m_contactNormal1.dot(body1.internalGetDeltaLinearVelocity()) + c.m_relpos1CrossNormal.dot(body1.internalGetDeltaAngularVelocity()); + const btScalar deltaVel2Dotn = c.m_contactNormal2.dot(body2.internalGetDeltaLinearVelocity()) + c.m_relpos2CrossNormal.dot(body2.internalGetDeltaAngularVelocity()); deltaImpulse -= deltaVel1Dotn*c.m_jacDiagABInv; deltaImpulse -= deltaVel2Dotn*c.m_jacDiagABInv; @@ -94,10 +93,10 @@ static btScalar gResolveSingleConstraintRowLowerLimit_scalar_reference(btSolverB { c.m_appliedImpulse = sum; } - bodyA.internalApplyImpulse(c.m_contactNormal1*bodyA.internalGetInvMass(), c.m_angularComponentA, deltaImpulse); - bodyB.internalApplyImpulse(c.m_contactNormal2*bodyB.internalGetInvMass(), c.m_angularComponentB, deltaImpulse); + body1.internalApplyImpulse(c.m_contactNormal1*body1.internalGetInvMass(), c.m_angularComponentA, deltaImpulse); + body2.internalApplyImpulse(c.m_contactNormal2*body2.internalGetInvMass(), c.m_angularComponentB, deltaImpulse); - return deltaImpulse*(1./c.m_jacDiagABInv); + return deltaImpulse; } @@ -150,14 +149,14 @@ static inline __m128 btSimdDot3( __m128 vec0, __m128 vec1 ) #endif // Project Gauss Seidel or the equivalent Sequential Impulse -static btScalar gResolveSingleConstraintRowGeneric_sse2(btSolverBody& bodyA, btSolverBody& bodyB, const btSolverConstraint& c) +static btSimdScalar gResolveSingleConstraintRowGeneric_sse2(btSolverBody& body1, btSolverBody& body2, const btSolverConstraint& c) { __m128 cpAppliedImp = _mm_set1_ps(c.m_appliedImpulse); __m128 lowerLimit1 = _mm_set1_ps(c.m_lowerLimit); __m128 upperLimit1 = _mm_set1_ps(c.m_upperLimit); btSimdScalar deltaImpulse = _mm_sub_ps(_mm_set1_ps(c.m_rhs), _mm_mul_ps(_mm_set1_ps(c.m_appliedImpulse), _mm_set1_ps(c.m_cfm))); - __m128 deltaVel1Dotn = _mm_add_ps(btSimdDot3(c.m_contactNormal1.mVec128, bodyA.internalGetDeltaLinearVelocity().mVec128), btSimdDot3(c.m_relpos1CrossNormal.mVec128, bodyA.internalGetDeltaAngularVelocity().mVec128)); - __m128 deltaVel2Dotn = _mm_add_ps(btSimdDot3(c.m_contactNormal2.mVec128, bodyB.internalGetDeltaLinearVelocity().mVec128), btSimdDot3(c.m_relpos2CrossNormal.mVec128, bodyB.internalGetDeltaAngularVelocity().mVec128)); + __m128 deltaVel1Dotn = _mm_add_ps(btSimdDot3(c.m_contactNormal1.mVec128, body1.internalGetDeltaLinearVelocity().mVec128), btSimdDot3(c.m_relpos1CrossNormal.mVec128, body1.internalGetDeltaAngularVelocity().mVec128)); + __m128 deltaVel2Dotn = _mm_add_ps(btSimdDot3(c.m_contactNormal2.mVec128, body2.internalGetDeltaLinearVelocity().mVec128), btSimdDot3(c.m_relpos2CrossNormal.mVec128, body2.internalGetDeltaAngularVelocity().mVec128)); deltaImpulse = _mm_sub_ps(deltaImpulse, _mm_mul_ps(deltaVel1Dotn, _mm_set1_ps(c.m_jacDiagABInv))); deltaImpulse = _mm_sub_ps(deltaImpulse, _mm_mul_ps(deltaVel2Dotn, _mm_set1_ps(c.m_jacDiagABInv))); btSimdScalar sum = _mm_add_ps(cpAppliedImp, deltaImpulse); @@ -170,27 +169,27 @@ static btScalar gResolveSingleConstraintRowGeneric_sse2(btSolverBody& bodyA, btS __m128 upperMinApplied = _mm_sub_ps(upperLimit1, cpAppliedImp); deltaImpulse = _mm_or_ps(_mm_and_ps(resultUpperLess, deltaImpulse), _mm_andnot_ps(resultUpperLess, upperMinApplied)); c.m_appliedImpulse = _mm_or_ps(_mm_and_ps(resultUpperLess, c.m_appliedImpulse), _mm_andnot_ps(resultUpperLess, upperLimit1)); - __m128 linearComponentA = _mm_mul_ps(c.m_contactNormal1.mVec128, bodyA.internalGetInvMass().mVec128); - __m128 linearComponentB = _mm_mul_ps((c.m_contactNormal2).mVec128, bodyB.internalGetInvMass().mVec128); + __m128 linearComponentA = _mm_mul_ps(c.m_contactNormal1.mVec128, body1.internalGetInvMass().mVec128); + __m128 linearComponentB = _mm_mul_ps((c.m_contactNormal2).mVec128, body2.internalGetInvMass().mVec128); __m128 impulseMagnitude = deltaImpulse; - bodyA.internalGetDeltaLinearVelocity().mVec128 = _mm_add_ps(bodyA.internalGetDeltaLinearVelocity().mVec128, _mm_mul_ps(linearComponentA, impulseMagnitude)); - bodyA.internalGetDeltaAngularVelocity().mVec128 = _mm_add_ps(bodyA.internalGetDeltaAngularVelocity().mVec128, _mm_mul_ps(c.m_angularComponentA.mVec128, impulseMagnitude)); - bodyB.internalGetDeltaLinearVelocity().mVec128 = _mm_add_ps(bodyB.internalGetDeltaLinearVelocity().mVec128, _mm_mul_ps(linearComponentB, impulseMagnitude)); - bodyB.internalGetDeltaAngularVelocity().mVec128 = _mm_add_ps(bodyB.internalGetDeltaAngularVelocity().mVec128, _mm_mul_ps(c.m_angularComponentB.mVec128, impulseMagnitude)); - return deltaImpulse.m_floats[0]/c.m_jacDiagABInv; + body1.internalGetDeltaLinearVelocity().mVec128 = _mm_add_ps(body1.internalGetDeltaLinearVelocity().mVec128, _mm_mul_ps(linearComponentA, impulseMagnitude)); + body1.internalGetDeltaAngularVelocity().mVec128 = _mm_add_ps(body1.internalGetDeltaAngularVelocity().mVec128, _mm_mul_ps(c.m_angularComponentA.mVec128, impulseMagnitude)); + body2.internalGetDeltaLinearVelocity().mVec128 = _mm_add_ps(body2.internalGetDeltaLinearVelocity().mVec128, _mm_mul_ps(linearComponentB, impulseMagnitude)); + body2.internalGetDeltaAngularVelocity().mVec128 = _mm_add_ps(body2.internalGetDeltaAngularVelocity().mVec128, _mm_mul_ps(c.m_angularComponentB.mVec128, impulseMagnitude)); + return deltaImpulse; } // Enhanced version of gResolveSingleConstraintRowGeneric_sse2 with SSE4.1 and FMA3 -static btScalar gResolveSingleConstraintRowGeneric_sse4_1_fma3(btSolverBody& bodyA, btSolverBody& bodyB, const btSolverConstraint& c) +static btSimdScalar gResolveSingleConstraintRowGeneric_sse4_1_fma3(btSolverBody& body1, btSolverBody& body2, const btSolverConstraint& c) { #if defined (BT_ALLOW_SSE4) __m128 tmp = _mm_set_ps1(c.m_jacDiagABInv); __m128 deltaImpulse = _mm_set_ps1(c.m_rhs - btScalar(c.m_appliedImpulse)*c.m_cfm); const __m128 lowerLimit = _mm_set_ps1(c.m_lowerLimit); const __m128 upperLimit = _mm_set_ps1(c.m_upperLimit); - const __m128 deltaVel1Dotn = _mm_add_ps(DOT_PRODUCT(c.m_contactNormal1.mVec128, bodyA.internalGetDeltaLinearVelocity().mVec128), DOT_PRODUCT(c.m_relpos1CrossNormal.mVec128, bodyA.internalGetDeltaAngularVelocity().mVec128)); - const __m128 deltaVel2Dotn = _mm_add_ps(DOT_PRODUCT(c.m_contactNormal2.mVec128, bodyB.internalGetDeltaLinearVelocity().mVec128), DOT_PRODUCT(c.m_relpos2CrossNormal.mVec128, bodyB.internalGetDeltaAngularVelocity().mVec128)); + const __m128 deltaVel1Dotn = _mm_add_ps(DOT_PRODUCT(c.m_contactNormal1.mVec128, body1.internalGetDeltaLinearVelocity().mVec128), DOT_PRODUCT(c.m_relpos1CrossNormal.mVec128, body1.internalGetDeltaAngularVelocity().mVec128)); + const __m128 deltaVel2Dotn = _mm_add_ps(DOT_PRODUCT(c.m_contactNormal2.mVec128, body2.internalGetDeltaLinearVelocity().mVec128), DOT_PRODUCT(c.m_relpos2CrossNormal.mVec128, body2.internalGetDeltaAngularVelocity().mVec128)); deltaImpulse = FMNADD(deltaVel1Dotn, tmp, deltaImpulse); deltaImpulse = FMNADD(deltaVel2Dotn, tmp, deltaImpulse); tmp = _mm_add_ps(c.m_appliedImpulse, deltaImpulse); // sum @@ -198,27 +197,26 @@ static btScalar gResolveSingleConstraintRowGeneric_sse4_1_fma3(btSolverBody& bod const __m128 maskUpper = _mm_cmpgt_ps(upperLimit, tmp); deltaImpulse = _mm_blendv_ps(_mm_sub_ps(lowerLimit, c.m_appliedImpulse), _mm_blendv_ps(_mm_sub_ps(upperLimit, c.m_appliedImpulse), deltaImpulse, maskUpper), maskLower); c.m_appliedImpulse = _mm_blendv_ps(lowerLimit, _mm_blendv_ps(upperLimit, tmp, maskUpper), maskLower); - bodyA.internalGetDeltaLinearVelocity().mVec128 = FMADD(_mm_mul_ps(c.m_contactNormal1.mVec128, bodyA.internalGetInvMass().mVec128), deltaImpulse, bodyA.internalGetDeltaLinearVelocity().mVec128); - bodyA.internalGetDeltaAngularVelocity().mVec128 = FMADD(c.m_angularComponentA.mVec128, deltaImpulse, bodyA.internalGetDeltaAngularVelocity().mVec128); - bodyB.internalGetDeltaLinearVelocity().mVec128 = FMADD(_mm_mul_ps(c.m_contactNormal2.mVec128, bodyB.internalGetInvMass().mVec128), deltaImpulse, bodyB.internalGetDeltaLinearVelocity().mVec128); - bodyB.internalGetDeltaAngularVelocity().mVec128 = FMADD(c.m_angularComponentB.mVec128, deltaImpulse, bodyB.internalGetDeltaAngularVelocity().mVec128); - btSimdScalar deltaImp = deltaImpulse; - return deltaImp.m_floats[0]*(1./c.m_jacDiagABInv); + body1.internalGetDeltaLinearVelocity().mVec128 = FMADD(_mm_mul_ps(c.m_contactNormal1.mVec128, body1.internalGetInvMass().mVec128), deltaImpulse, body1.internalGetDeltaLinearVelocity().mVec128); + body1.internalGetDeltaAngularVelocity().mVec128 = FMADD(c.m_angularComponentA.mVec128, deltaImpulse, body1.internalGetDeltaAngularVelocity().mVec128); + body2.internalGetDeltaLinearVelocity().mVec128 = FMADD(_mm_mul_ps(c.m_contactNormal2.mVec128, body2.internalGetInvMass().mVec128), deltaImpulse, body2.internalGetDeltaLinearVelocity().mVec128); + body2.internalGetDeltaAngularVelocity().mVec128 = FMADD(c.m_angularComponentB.mVec128, deltaImpulse, body2.internalGetDeltaAngularVelocity().mVec128); + return deltaImpulse; #else - return gResolveSingleConstraintRowGeneric_sse2(bodyA,bodyB,c); + return gResolveSingleConstraintRowGeneric_sse2(body1,body2,c); #endif } -static btScalar gResolveSingleConstraintRowLowerLimit_sse2(btSolverBody& bodyA, btSolverBody& bodyB, const btSolverConstraint& c) +static btSimdScalar gResolveSingleConstraintRowLowerLimit_sse2(btSolverBody& body1, btSolverBody& body2, const btSolverConstraint& c) { __m128 cpAppliedImp = _mm_set1_ps(c.m_appliedImpulse); __m128 lowerLimit1 = _mm_set1_ps(c.m_lowerLimit); __m128 upperLimit1 = _mm_set1_ps(c.m_upperLimit); btSimdScalar deltaImpulse = _mm_sub_ps(_mm_set1_ps(c.m_rhs), _mm_mul_ps(_mm_set1_ps(c.m_appliedImpulse), _mm_set1_ps(c.m_cfm))); - __m128 deltaVel1Dotn = _mm_add_ps(btSimdDot3(c.m_contactNormal1.mVec128, bodyA.internalGetDeltaLinearVelocity().mVec128), btSimdDot3(c.m_relpos1CrossNormal.mVec128, bodyA.internalGetDeltaAngularVelocity().mVec128)); - __m128 deltaVel2Dotn = _mm_add_ps(btSimdDot3(c.m_contactNormal2.mVec128, bodyB.internalGetDeltaLinearVelocity().mVec128), btSimdDot3(c.m_relpos2CrossNormal.mVec128, bodyB.internalGetDeltaAngularVelocity().mVec128)); + __m128 deltaVel1Dotn = _mm_add_ps(btSimdDot3(c.m_contactNormal1.mVec128, body1.internalGetDeltaLinearVelocity().mVec128), btSimdDot3(c.m_relpos1CrossNormal.mVec128, body1.internalGetDeltaAngularVelocity().mVec128)); + __m128 deltaVel2Dotn = _mm_add_ps(btSimdDot3(c.m_contactNormal2.mVec128, body2.internalGetDeltaLinearVelocity().mVec128), btSimdDot3(c.m_relpos2CrossNormal.mVec128, body2.internalGetDeltaAngularVelocity().mVec128)); deltaImpulse = _mm_sub_ps(deltaImpulse, _mm_mul_ps(deltaVel1Dotn, _mm_set1_ps(c.m_jacDiagABInv))); deltaImpulse = _mm_sub_ps(deltaImpulse, _mm_mul_ps(deltaVel2Dotn, _mm_set1_ps(c.m_jacDiagABInv))); btSimdScalar sum = _mm_add_ps(cpAppliedImp, deltaImpulse); @@ -228,40 +226,39 @@ static btScalar gResolveSingleConstraintRowLowerLimit_sse2(btSolverBody& bodyA, __m128 lowMinApplied = _mm_sub_ps(lowerLimit1, cpAppliedImp); deltaImpulse = _mm_or_ps(_mm_and_ps(resultLowerLess, lowMinApplied), _mm_andnot_ps(resultLowerLess, deltaImpulse)); c.m_appliedImpulse = _mm_or_ps(_mm_and_ps(resultLowerLess, lowerLimit1), _mm_andnot_ps(resultLowerLess, sum)); - __m128 linearComponentA = _mm_mul_ps(c.m_contactNormal1.mVec128, bodyA.internalGetInvMass().mVec128); - __m128 linearComponentB = _mm_mul_ps(c.m_contactNormal2.mVec128, bodyB.internalGetInvMass().mVec128); + __m128 linearComponentA = _mm_mul_ps(c.m_contactNormal1.mVec128, body1.internalGetInvMass().mVec128); + __m128 linearComponentB = _mm_mul_ps(c.m_contactNormal2.mVec128, body2.internalGetInvMass().mVec128); __m128 impulseMagnitude = deltaImpulse; - bodyA.internalGetDeltaLinearVelocity().mVec128 = _mm_add_ps(bodyA.internalGetDeltaLinearVelocity().mVec128, _mm_mul_ps(linearComponentA, impulseMagnitude)); - bodyA.internalGetDeltaAngularVelocity().mVec128 = _mm_add_ps(bodyA.internalGetDeltaAngularVelocity().mVec128, _mm_mul_ps(c.m_angularComponentA.mVec128, impulseMagnitude)); - bodyB.internalGetDeltaLinearVelocity().mVec128 = _mm_add_ps(bodyB.internalGetDeltaLinearVelocity().mVec128, _mm_mul_ps(linearComponentB, impulseMagnitude)); - bodyB.internalGetDeltaAngularVelocity().mVec128 = _mm_add_ps(bodyB.internalGetDeltaAngularVelocity().mVec128, _mm_mul_ps(c.m_angularComponentB.mVec128, impulseMagnitude)); - return deltaImpulse.m_floats[0]/c.m_jacDiagABInv; + body1.internalGetDeltaLinearVelocity().mVec128 = _mm_add_ps(body1.internalGetDeltaLinearVelocity().mVec128, _mm_mul_ps(linearComponentA, impulseMagnitude)); + body1.internalGetDeltaAngularVelocity().mVec128 = _mm_add_ps(body1.internalGetDeltaAngularVelocity().mVec128, _mm_mul_ps(c.m_angularComponentA.mVec128, impulseMagnitude)); + body2.internalGetDeltaLinearVelocity().mVec128 = _mm_add_ps(body2.internalGetDeltaLinearVelocity().mVec128, _mm_mul_ps(linearComponentB, impulseMagnitude)); + body2.internalGetDeltaAngularVelocity().mVec128 = _mm_add_ps(body2.internalGetDeltaAngularVelocity().mVec128, _mm_mul_ps(c.m_angularComponentB.mVec128, impulseMagnitude)); + return deltaImpulse; } // Enhanced version of gResolveSingleConstraintRowGeneric_sse2 with SSE4.1 and FMA3 -static btScalar gResolveSingleConstraintRowLowerLimit_sse4_1_fma3(btSolverBody& bodyA, btSolverBody& bodyB, const btSolverConstraint& c) +static btSimdScalar gResolveSingleConstraintRowLowerLimit_sse4_1_fma3(btSolverBody& body1, btSolverBody& body2, const btSolverConstraint& c) { #ifdef BT_ALLOW_SSE4 __m128 tmp = _mm_set_ps1(c.m_jacDiagABInv); __m128 deltaImpulse = _mm_set_ps1(c.m_rhs - btScalar(c.m_appliedImpulse)*c.m_cfm); const __m128 lowerLimit = _mm_set_ps1(c.m_lowerLimit); - const __m128 deltaVel1Dotn = _mm_add_ps(DOT_PRODUCT(c.m_contactNormal1.mVec128, bodyA.internalGetDeltaLinearVelocity().mVec128), DOT_PRODUCT(c.m_relpos1CrossNormal.mVec128, bodyA.internalGetDeltaAngularVelocity().mVec128)); - const __m128 deltaVel2Dotn = _mm_add_ps(DOT_PRODUCT(c.m_contactNormal2.mVec128, bodyB.internalGetDeltaLinearVelocity().mVec128), DOT_PRODUCT(c.m_relpos2CrossNormal.mVec128, bodyB.internalGetDeltaAngularVelocity().mVec128)); + const __m128 deltaVel1Dotn = _mm_add_ps(DOT_PRODUCT(c.m_contactNormal1.mVec128, body1.internalGetDeltaLinearVelocity().mVec128), DOT_PRODUCT(c.m_relpos1CrossNormal.mVec128, body1.internalGetDeltaAngularVelocity().mVec128)); + const __m128 deltaVel2Dotn = _mm_add_ps(DOT_PRODUCT(c.m_contactNormal2.mVec128, body2.internalGetDeltaLinearVelocity().mVec128), DOT_PRODUCT(c.m_relpos2CrossNormal.mVec128, body2.internalGetDeltaAngularVelocity().mVec128)); deltaImpulse = FMNADD(deltaVel1Dotn, tmp, deltaImpulse); deltaImpulse = FMNADD(deltaVel2Dotn, tmp, deltaImpulse); tmp = _mm_add_ps(c.m_appliedImpulse, deltaImpulse); const __m128 mask = _mm_cmpgt_ps(tmp, lowerLimit); deltaImpulse = _mm_blendv_ps(_mm_sub_ps(lowerLimit, c.m_appliedImpulse), deltaImpulse, mask); c.m_appliedImpulse = _mm_blendv_ps(lowerLimit, tmp, mask); - bodyA.internalGetDeltaLinearVelocity().mVec128 = FMADD(_mm_mul_ps(c.m_contactNormal1.mVec128, bodyA.internalGetInvMass().mVec128), deltaImpulse, bodyA.internalGetDeltaLinearVelocity().mVec128); - bodyA.internalGetDeltaAngularVelocity().mVec128 = FMADD(c.m_angularComponentA.mVec128, deltaImpulse, bodyA.internalGetDeltaAngularVelocity().mVec128); - bodyB.internalGetDeltaLinearVelocity().mVec128 = FMADD(_mm_mul_ps(c.m_contactNormal2.mVec128, bodyB.internalGetInvMass().mVec128), deltaImpulse, bodyB.internalGetDeltaLinearVelocity().mVec128); - bodyB.internalGetDeltaAngularVelocity().mVec128 = FMADD(c.m_angularComponentB.mVec128, deltaImpulse, bodyB.internalGetDeltaAngularVelocity().mVec128); - btSimdScalar deltaImp = deltaImpulse; - return deltaImp.m_floats[0]*(1./c.m_jacDiagABInv); + body1.internalGetDeltaLinearVelocity().mVec128 = FMADD(_mm_mul_ps(c.m_contactNormal1.mVec128, body1.internalGetInvMass().mVec128), deltaImpulse, body1.internalGetDeltaLinearVelocity().mVec128); + body1.internalGetDeltaAngularVelocity().mVec128 = FMADD(c.m_angularComponentA.mVec128, deltaImpulse, body1.internalGetDeltaAngularVelocity().mVec128); + body2.internalGetDeltaLinearVelocity().mVec128 = FMADD(_mm_mul_ps(c.m_contactNormal2.mVec128, body2.internalGetInvMass().mVec128), deltaImpulse, body2.internalGetDeltaLinearVelocity().mVec128); + body2.internalGetDeltaAngularVelocity().mVec128 = FMADD(c.m_angularComponentB.mVec128, deltaImpulse, body2.internalGetDeltaAngularVelocity().mVec128); + return deltaImpulse; #else - return gResolveSingleConstraintRowLowerLimit_sse2(bodyA,bodyB,c); + return gResolveSingleConstraintRowLowerLimit_sse2(body1,body2,c); #endif //BT_ALLOW_SSE4 } @@ -270,32 +267,32 @@ static btScalar gResolveSingleConstraintRowLowerLimit_sse4_1_fma3(btSolverBody& -btScalar btSequentialImpulseConstraintSolver::resolveSingleConstraintRowGenericSIMD(btSolverBody& bodyA,btSolverBody& bodyB,const btSolverConstraint& c) +btSimdScalar btSequentialImpulseConstraintSolver::resolveSingleConstraintRowGenericSIMD(btSolverBody& body1,btSolverBody& body2,const btSolverConstraint& c) { - return m_resolveSingleConstraintRowGeneric(bodyA, bodyB, c); + return m_resolveSingleConstraintRowGeneric(body1, body2, c); } // Project Gauss Seidel or the equivalent Sequential Impulse -btScalar btSequentialImpulseConstraintSolver::resolveSingleConstraintRowGeneric(btSolverBody& bodyA,btSolverBody& bodyB,const btSolverConstraint& c) +btSimdScalar btSequentialImpulseConstraintSolver::resolveSingleConstraintRowGeneric(btSolverBody& body1,btSolverBody& body2,const btSolverConstraint& c) { - return m_resolveSingleConstraintRowGeneric(bodyA, bodyB, c); + return m_resolveSingleConstraintRowGeneric(body1, body2, c); } -btScalar btSequentialImpulseConstraintSolver::resolveSingleConstraintRowLowerLimitSIMD(btSolverBody& bodyA,btSolverBody& bodyB,const btSolverConstraint& c) +btSimdScalar btSequentialImpulseConstraintSolver::resolveSingleConstraintRowLowerLimitSIMD(btSolverBody& body1,btSolverBody& body2,const btSolverConstraint& c) { - return m_resolveSingleConstraintRowLowerLimit(bodyA, bodyB, c); + return m_resolveSingleConstraintRowLowerLimit(body1, body2, c); } -btScalar btSequentialImpulseConstraintSolver::resolveSingleConstraintRowLowerLimit(btSolverBody& bodyA,btSolverBody& bodyB,const btSolverConstraint& c) +btSimdScalar btSequentialImpulseConstraintSolver::resolveSingleConstraintRowLowerLimit(btSolverBody& body1,btSolverBody& body2,const btSolverConstraint& c) { - return m_resolveSingleConstraintRowLowerLimit(bodyA, bodyB, c); + return m_resolveSingleConstraintRowLowerLimit(body1, body2, c); } -static btScalar gResolveSplitPenetrationImpulse_scalar_reference( - btSolverBody& bodyA, - btSolverBody& bodyB, +static btSimdScalar gResolveSplitPenetrationImpulse_scalar_reference( + btSolverBody& body1, + btSolverBody& body2, const btSolverConstraint& c) { btScalar deltaImpulse = 0.f; @@ -304,8 +301,8 @@ static btScalar gResolveSplitPenetrationImpulse_scalar_reference( { gNumSplitImpulseRecoveries++; deltaImpulse = c.m_rhsPenetration-btScalar(c.m_appliedPushImpulse)*c.m_cfm; - const btScalar deltaVel1Dotn = c.m_contactNormal1.dot(bodyA.internalGetPushVelocity()) + c.m_relpos1CrossNormal.dot(bodyA.internalGetTurnVelocity()); - const btScalar deltaVel2Dotn = c.m_contactNormal2.dot(bodyB.internalGetPushVelocity()) + c.m_relpos2CrossNormal.dot(bodyB.internalGetTurnVelocity()); + const btScalar deltaVel1Dotn = c.m_contactNormal1.dot(body1.internalGetPushVelocity()) + c.m_relpos1CrossNormal.dot(body1.internalGetTurnVelocity()); + const btScalar deltaVel2Dotn = c.m_contactNormal2.dot(body2.internalGetPushVelocity()) + c.m_relpos2CrossNormal.dot(body2.internalGetTurnVelocity()); deltaImpulse -= deltaVel1Dotn*c.m_jacDiagABInv; deltaImpulse -= deltaVel2Dotn*c.m_jacDiagABInv; @@ -319,13 +316,13 @@ static btScalar gResolveSplitPenetrationImpulse_scalar_reference( { c.m_appliedPushImpulse = sum; } - bodyA.internalApplyPushImpulse(c.m_contactNormal1*bodyA.internalGetInvMass(),c.m_angularComponentA,deltaImpulse); - bodyB.internalApplyPushImpulse(c.m_contactNormal2*bodyB.internalGetInvMass(),c.m_angularComponentB,deltaImpulse); + body1.internalApplyPushImpulse(c.m_contactNormal1*body1.internalGetInvMass(),c.m_angularComponentA,deltaImpulse); + body2.internalApplyPushImpulse(c.m_contactNormal2*body2.internalGetInvMass(),c.m_angularComponentB,deltaImpulse); } - return deltaImpulse*(1./c.m_jacDiagABInv); + return deltaImpulse; } -static btScalar gResolveSplitPenetrationImpulse_sse2(btSolverBody& bodyA,btSolverBody& bodyB,const btSolverConstraint& c) +static btSimdScalar gResolveSplitPenetrationImpulse_sse2(btSolverBody& body1,btSolverBody& body2,const btSolverConstraint& c) { #ifdef USE_SIMD if (!c.m_rhsPenetration) @@ -337,8 +334,8 @@ static btScalar gResolveSplitPenetrationImpulse_sse2(btSolverBody& bodyA,btSolve __m128 lowerLimit1 = _mm_set1_ps(c.m_lowerLimit); __m128 upperLimit1 = _mm_set1_ps(c.m_upperLimit); __m128 deltaImpulse = _mm_sub_ps(_mm_set1_ps(c.m_rhsPenetration), _mm_mul_ps(_mm_set1_ps(c.m_appliedPushImpulse),_mm_set1_ps(c.m_cfm))); - __m128 deltaVel1Dotn = _mm_add_ps(btSimdDot3(c.m_contactNormal1.mVec128,bodyA.internalGetPushVelocity().mVec128), btSimdDot3(c.m_relpos1CrossNormal.mVec128,bodyA.internalGetTurnVelocity().mVec128)); - __m128 deltaVel2Dotn = _mm_add_ps(btSimdDot3(c.m_contactNormal2.mVec128,bodyB.internalGetPushVelocity().mVec128), btSimdDot3(c.m_relpos2CrossNormal.mVec128,bodyB.internalGetTurnVelocity().mVec128)); + __m128 deltaVel1Dotn = _mm_add_ps(btSimdDot3(c.m_contactNormal1.mVec128,body1.internalGetPushVelocity().mVec128), btSimdDot3(c.m_relpos1CrossNormal.mVec128,body1.internalGetTurnVelocity().mVec128)); + __m128 deltaVel2Dotn = _mm_add_ps(btSimdDot3(c.m_contactNormal2.mVec128,body2.internalGetPushVelocity().mVec128), btSimdDot3(c.m_relpos2CrossNormal.mVec128,body2.internalGetTurnVelocity().mVec128)); deltaImpulse = _mm_sub_ps(deltaImpulse,_mm_mul_ps(deltaVel1Dotn,_mm_set1_ps(c.m_jacDiagABInv))); deltaImpulse = _mm_sub_ps(deltaImpulse,_mm_mul_ps(deltaVel2Dotn,_mm_set1_ps(c.m_jacDiagABInv))); btSimdScalar sum = _mm_add_ps(cpAppliedImp,deltaImpulse); @@ -348,17 +345,16 @@ static btScalar gResolveSplitPenetrationImpulse_sse2(btSolverBody& bodyA,btSolve __m128 lowMinApplied = _mm_sub_ps(lowerLimit1,cpAppliedImp); deltaImpulse = _mm_or_ps( _mm_and_ps(resultLowerLess, lowMinApplied), _mm_andnot_ps(resultLowerLess, deltaImpulse) ); c.m_appliedPushImpulse = _mm_or_ps( _mm_and_ps(resultLowerLess, lowerLimit1), _mm_andnot_ps(resultLowerLess, sum) ); - __m128 linearComponentA = _mm_mul_ps(c.m_contactNormal1.mVec128,bodyA.internalGetInvMass().mVec128); - __m128 linearComponentB = _mm_mul_ps(c.m_contactNormal2.mVec128,bodyB.internalGetInvMass().mVec128); + __m128 linearComponentA = _mm_mul_ps(c.m_contactNormal1.mVec128,body1.internalGetInvMass().mVec128); + __m128 linearComponentB = _mm_mul_ps(c.m_contactNormal2.mVec128,body2.internalGetInvMass().mVec128); __m128 impulseMagnitude = deltaImpulse; - bodyA.internalGetPushVelocity().mVec128 = _mm_add_ps(bodyA.internalGetPushVelocity().mVec128,_mm_mul_ps(linearComponentA,impulseMagnitude)); - bodyA.internalGetTurnVelocity().mVec128 = _mm_add_ps(bodyA.internalGetTurnVelocity().mVec128 ,_mm_mul_ps(c.m_angularComponentA.mVec128,impulseMagnitude)); - bodyB.internalGetPushVelocity().mVec128 = _mm_add_ps(bodyB.internalGetPushVelocity().mVec128,_mm_mul_ps(linearComponentB,impulseMagnitude)); - bodyB.internalGetTurnVelocity().mVec128 = _mm_add_ps(bodyB.internalGetTurnVelocity().mVec128 ,_mm_mul_ps(c.m_angularComponentB.mVec128,impulseMagnitude)); - btSimdScalar deltaImp = deltaImpulse; - return deltaImp.m_floats[0] * (1. / c.m_jacDiagABInv); + body1.internalGetPushVelocity().mVec128 = _mm_add_ps(body1.internalGetPushVelocity().mVec128,_mm_mul_ps(linearComponentA,impulseMagnitude)); + body1.internalGetTurnVelocity().mVec128 = _mm_add_ps(body1.internalGetTurnVelocity().mVec128 ,_mm_mul_ps(c.m_angularComponentA.mVec128,impulseMagnitude)); + body2.internalGetPushVelocity().mVec128 = _mm_add_ps(body2.internalGetPushVelocity().mVec128,_mm_mul_ps(linearComponentB,impulseMagnitude)); + body2.internalGetTurnVelocity().mVec128 = _mm_add_ps(body2.internalGetTurnVelocity().mVec128 ,_mm_mul_ps(c.m_angularComponentB.mVec128,impulseMagnitude)); + return deltaImpulse; #else - return gResolveSplitPenetrationImpulse_scalar_reference(bodyA,bodyB,c); + return gResolveSplitPenetrationImpulse_scalar_reference(body1,body2,c); #endif } @@ -552,7 +548,7 @@ void btSequentialImpulseConstraintSolver::setupFrictionConstraint(btSolverConstr btSolverBody& solverBodyB = m_tmpSolverBodyPool[solverBodyIdB]; btRigidBody* body0 = m_tmpSolverBodyPool[solverBodyIdA].m_originalBody; - btRigidBody* bodyA = m_tmpSolverBodyPool[solverBodyIdB].m_originalBody; + btRigidBody* body1 = m_tmpSolverBodyPool[solverBodyIdB].m_originalBody; solverConstraint.m_solverBodyIdA = solverBodyIdA; solverConstraint.m_solverBodyIdB = solverBodyIdB; @@ -576,12 +572,12 @@ void btSequentialImpulseConstraintSolver::setupFrictionConstraint(btSolverConstr solverConstraint.m_angularComponentA .setZero(); } - if (bodyA) + if (body1) { solverConstraint.m_contactNormal2 = -normalAxis; btVector3 ftorqueAxis1 = rel_pos2.cross(solverConstraint.m_contactNormal2); solverConstraint.m_relpos2CrossNormal = ftorqueAxis1; - solverConstraint.m_angularComponentB = bodyA->getInvInertiaTensorWorld()*ftorqueAxis1*bodyA->getAngularFactor(); + solverConstraint.m_angularComponentB = body1->getInvInertiaTensorWorld()*ftorqueAxis1*body1->getAngularFactor(); } else { solverConstraint.m_contactNormal2.setZero(); @@ -598,10 +594,10 @@ void btSequentialImpulseConstraintSolver::setupFrictionConstraint(btSolverConstr vec = ( solverConstraint.m_angularComponentA).cross(rel_pos1); denom0 = body0->getInvMass() + normalAxis.dot(vec); } - if (bodyA) + if (body1) { vec = ( -solverConstraint.m_angularComponentB).cross(rel_pos2); - denom1 = bodyA->getInvMass() + normalAxis.dot(vec); + denom1 = body1->getInvMass() + normalAxis.dot(vec); } btScalar denom = relaxation/(denom0+denom1); solverConstraint.m_jacDiagABInv = denom; @@ -613,8 +609,8 @@ void btSequentialImpulseConstraintSolver::setupFrictionConstraint(btSolverConstr btScalar rel_vel; btScalar vel1Dotn = solverConstraint.m_contactNormal1.dot(body0?solverBodyA.m_linearVelocity+solverBodyA.m_externalForceImpulse:btVector3(0,0,0)) + solverConstraint.m_relpos1CrossNormal.dot(body0?solverBodyA.m_angularVelocity:btVector3(0,0,0)); - btScalar vel2Dotn = solverConstraint.m_contactNormal2.dot(bodyA?solverBodyB.m_linearVelocity+solverBodyB.m_externalForceImpulse:btVector3(0,0,0)) - + solverConstraint.m_relpos2CrossNormal.dot(bodyA?solverBodyB.m_angularVelocity:btVector3(0,0,0)); + btScalar vel2Dotn = solverConstraint.m_contactNormal2.dot(body1?solverBodyB.m_linearVelocity+solverBodyB.m_externalForceImpulse:btVector3(0,0,0)) + + solverConstraint.m_relpos2CrossNormal.dot(body1?solverBodyB.m_angularVelocity:btVector3(0,0,0)); rel_vel = vel1Dotn+vel2Dotn; @@ -666,7 +662,7 @@ void btSequentialImpulseConstraintSolver::setupTorsionalFrictionConstraint( btSo btSolverBody& solverBodyB = m_tmpSolverBodyPool[solverBodyIdB]; btRigidBody* body0 = m_tmpSolverBodyPool[solverBodyIdA].m_originalBody; - btRigidBody* bodyA = m_tmpSolverBodyPool[solverBodyIdB].m_originalBody; + btRigidBody* body1 = m_tmpSolverBodyPool[solverBodyIdB].m_originalBody; solverConstraint.m_solverBodyIdA = solverBodyIdA; solverConstraint.m_solverBodyIdB = solverBodyIdB; @@ -685,13 +681,13 @@ void btSequentialImpulseConstraintSolver::setupTorsionalFrictionConstraint( btSo { btVector3 ftorqueAxis1 = normalAxis1; solverConstraint.m_relpos2CrossNormal = ftorqueAxis1; - solverConstraint.m_angularComponentB = bodyA ? bodyA->getInvInertiaTensorWorld()*ftorqueAxis1*bodyA->getAngularFactor() : btVector3(0,0,0); + solverConstraint.m_angularComponentB = body1 ? body1->getInvInertiaTensorWorld()*ftorqueAxis1*body1->getAngularFactor() : btVector3(0,0,0); } { btVector3 iMJaA = body0?body0->getInvInertiaTensorWorld()*solverConstraint.m_relpos1CrossNormal:btVector3(0,0,0); - btVector3 iMJaB = bodyA?bodyA->getInvInertiaTensorWorld()*solverConstraint.m_relpos2CrossNormal:btVector3(0,0,0); + btVector3 iMJaB = body1?body1->getInvInertiaTensorWorld()*solverConstraint.m_relpos2CrossNormal:btVector3(0,0,0); btScalar sum = 0; sum += iMJaA.dot(solverConstraint.m_relpos1CrossNormal); sum += iMJaB.dot(solverConstraint.m_relpos2CrossNormal); @@ -704,8 +700,8 @@ void btSequentialImpulseConstraintSolver::setupTorsionalFrictionConstraint( btSo btScalar rel_vel; btScalar vel1Dotn = solverConstraint.m_contactNormal1.dot(body0?solverBodyA.m_linearVelocity+solverBodyA.m_externalForceImpulse:btVector3(0,0,0)) + solverConstraint.m_relpos1CrossNormal.dot(body0?solverBodyA.m_angularVelocity:btVector3(0,0,0)); - btScalar vel2Dotn = solverConstraint.m_contactNormal2.dot(bodyA?solverBodyB.m_linearVelocity+solverBodyB.m_externalForceImpulse:btVector3(0,0,0)) - + solverConstraint.m_relpos2CrossNormal.dot(bodyA?solverBodyB.m_angularVelocity:btVector3(0,0,0)); + btScalar vel2Dotn = solverConstraint.m_contactNormal2.dot(body1?solverBodyB.m_linearVelocity+solverBodyB.m_externalForceImpulse:btVector3(0,0,0)) + + solverConstraint.m_relpos2CrossNormal.dot(body1?solverBodyB.m_angularVelocity:btVector3(0,0,0)); rel_vel = vel1Dotn+vel2Dotn; @@ -742,21 +738,23 @@ int btSequentialImpulseConstraintSolver::getOrInitSolverBody(btCollisionObject& { #if BT_THREADSAFE int solverBodyId = -1; - bool isRigidBodyType = btRigidBody::upcast( &body ) != NULL; - if ( isRigidBodyType && !body.isStaticOrKinematicObject() ) + if ( !body.isStaticOrKinematicObject() ) { // dynamic body // Dynamic bodies can only be in one island, so it's safe to write to the companionId solverBodyId = body.getCompanionId(); if ( solverBodyId < 0 ) { - solverBodyId = m_tmpSolverBodyPool.size(); - btSolverBody& solverBody = m_tmpSolverBodyPool.expand(); - initSolverBody( &solverBody, &body, timeStep ); - body.setCompanionId( solverBodyId ); + if ( btRigidBody* rb = btRigidBody::upcast( &body ) ) + { + solverBodyId = m_tmpSolverBodyPool.size(); + btSolverBody& solverBody = m_tmpSolverBodyPool.expand(); + initSolverBody( &solverBody, &body, timeStep ); + body.setCompanionId( solverBodyId ); + } } } - else if (isRigidBodyType && body.isKinematicObject()) + else if (body.isKinematicObject()) { // // NOTE: must test for kinematic before static because some kinematic objects also @@ -776,6 +774,7 @@ int btSequentialImpulseConstraintSolver::getOrInitSolverBody(btCollisionObject& if ( solverBodyId == INVALID_SOLVER_BODY_ID ) { // create a table entry for this body + btRigidBody* rb = btRigidBody::upcast( &body ); solverBodyId = m_tmpSolverBodyPool.size(); btSolverBody& solverBody = m_tmpSolverBodyPool.expand(); initSolverBody( &solverBody, &body, timeStep ); @@ -784,14 +783,6 @@ int btSequentialImpulseConstraintSolver::getOrInitSolverBody(btCollisionObject& } else { - bool isMultiBodyType = (body.getInternalType()&btCollisionObject::CO_FEATHERSTONE_LINK); - const bool isGhostType = (body.getInternalType() & btCollisionObject::CO_GHOST_OBJECT); - // Incorrectly set collision object flags can degrade performance in various ways. - if (!isMultiBodyType && !isGhostType) - { - btAssert( body.isStaticOrKinematicObject() ); - } - //it could be a multibody link collider // all fixed bodies (inf mass) get mapped to a single solver id if ( m_fixedBodyId < 0 ) { @@ -801,7 +792,7 @@ int btSequentialImpulseConstraintSolver::getOrInitSolverBody(btCollisionObject& } solverBodyId = m_fixedBodyId; } - btAssert( solverBodyId >= 0 && solverBodyId < m_tmpSolverBodyPool.size() ); + btAssert( solverBodyId < m_tmpSolverBodyPool.size() ); return solverBodyId; #else // BT_THREADSAFE @@ -1267,256 +1258,6 @@ void btSequentialImpulseConstraintSolver::convertContacts(btPersistentManifold** } } - -void btSequentialImpulseConstraintSolver::convertJoint(btSolverConstraint* currentConstraintRow, - btTypedConstraint* constraint, - const btTypedConstraint::btConstraintInfo1& info1, - int solverBodyIdA, - int solverBodyIdB, - const btContactSolverInfo& infoGlobal - ) -{ - const btRigidBody& rbA = constraint->getRigidBodyA(); - const btRigidBody& rbB = constraint->getRigidBodyB(); - - const btSolverBody* bodyAPtr = &m_tmpSolverBodyPool[solverBodyIdA]; - const btSolverBody* bodyBPtr = &m_tmpSolverBodyPool[solverBodyIdB]; - - int overrideNumSolverIterations = constraint->getOverrideNumSolverIterations() > 0 ? constraint->getOverrideNumSolverIterations() : infoGlobal.m_numIterations; - if (overrideNumSolverIterations>m_maxOverrideNumSolverIterations) - m_maxOverrideNumSolverIterations = overrideNumSolverIterations; - - for (int j=0;jgetDeltaLinearVelocity().isZero()); - btAssert(bodyAPtr->getDeltaAngularVelocity().isZero()); - btAssert(bodyAPtr->getPushVelocity().isZero()); - btAssert(bodyAPtr->getTurnVelocity().isZero()); - btAssert(bodyBPtr->getDeltaLinearVelocity().isZero()); - btAssert(bodyBPtr->getDeltaAngularVelocity().isZero()); - btAssert(bodyBPtr->getPushVelocity().isZero()); - btAssert(bodyBPtr->getTurnVelocity().isZero()); - //bodyAPtr->internalGetDeltaLinearVelocity().setValue(0.f,0.f,0.f); - //bodyAPtr->internalGetDeltaAngularVelocity().setValue(0.f,0.f,0.f); - //bodyAPtr->internalGetPushVelocity().setValue(0.f,0.f,0.f); - //bodyAPtr->internalGetTurnVelocity().setValue(0.f,0.f,0.f); - //bodyBPtr->internalGetDeltaLinearVelocity().setValue(0.f,0.f,0.f); - //bodyBPtr->internalGetDeltaAngularVelocity().setValue(0.f,0.f,0.f); - //bodyBPtr->internalGetPushVelocity().setValue(0.f,0.f,0.f); - //bodyBPtr->internalGetTurnVelocity().setValue(0.f,0.f,0.f); - - - btTypedConstraint::btConstraintInfo2 info2; - info2.fps = 1.f/infoGlobal.m_timeStep; - info2.erp = infoGlobal.m_erp; - info2.m_J1linearAxis = currentConstraintRow->m_contactNormal1; - info2.m_J1angularAxis = currentConstraintRow->m_relpos1CrossNormal; - info2.m_J2linearAxis = currentConstraintRow->m_contactNormal2; - info2.m_J2angularAxis = currentConstraintRow->m_relpos2CrossNormal; - info2.rowskip = sizeof(btSolverConstraint)/sizeof(btScalar);//check this - ///the size of btSolverConstraint needs be a multiple of btScalar - btAssert(info2.rowskip*sizeof(btScalar)== sizeof(btSolverConstraint)); - info2.m_constraintError = ¤tConstraintRow->m_rhs; - currentConstraintRow->m_cfm = infoGlobal.m_globalCfm; - info2.m_damping = infoGlobal.m_damping; - info2.cfm = ¤tConstraintRow->m_cfm; - info2.m_lowerLimit = ¤tConstraintRow->m_lowerLimit; - info2.m_upperLimit = ¤tConstraintRow->m_upperLimit; - info2.m_numIterations = infoGlobal.m_numIterations; - constraint->getInfo2(&info2); - - ///finalize the constraint setup - for (int j=0;j=constraint->getBreakingImpulseThreshold()) - { - solverConstraint.m_upperLimit = constraint->getBreakingImpulseThreshold(); - } - - if (solverConstraint.m_lowerLimit<=-constraint->getBreakingImpulseThreshold()) - { - solverConstraint.m_lowerLimit = -constraint->getBreakingImpulseThreshold(); - } - - solverConstraint.m_originalContactPoint = constraint; - - { - const btVector3& ftorqueAxis1 = solverConstraint.m_relpos1CrossNormal; - solverConstraint.m_angularComponentA = constraint->getRigidBodyA().getInvInertiaTensorWorld()*ftorqueAxis1*constraint->getRigidBodyA().getAngularFactor(); - } - { - const btVector3& ftorqueAxis2 = solverConstraint.m_relpos2CrossNormal; - solverConstraint.m_angularComponentB = constraint->getRigidBodyB().getInvInertiaTensorWorld()*ftorqueAxis2*constraint->getRigidBodyB().getAngularFactor(); - } - - { - btVector3 iMJlA = solverConstraint.m_contactNormal1*rbA.getInvMass(); - btVector3 iMJaA = rbA.getInvInertiaTensorWorld()*solverConstraint.m_relpos1CrossNormal; - btVector3 iMJlB = solverConstraint.m_contactNormal2*rbB.getInvMass();//sign of normal? - btVector3 iMJaB = rbB.getInvInertiaTensorWorld()*solverConstraint.m_relpos2CrossNormal; - - btScalar sum = iMJlA.dot(solverConstraint.m_contactNormal1); - sum += iMJaA.dot(solverConstraint.m_relpos1CrossNormal); - sum += iMJlB.dot(solverConstraint.m_contactNormal2); - sum += iMJaB.dot(solverConstraint.m_relpos2CrossNormal); - btScalar fsum = btFabs(sum); - btAssert(fsum > SIMD_EPSILON); - btScalar sorRelaxation = 1.f;//todo: get from globalInfo? - solverConstraint.m_jacDiagABInv = fsum>SIMD_EPSILON?sorRelaxation/sum : 0.f; - } - - { - btScalar rel_vel; - btVector3 externalForceImpulseA = bodyAPtr->m_originalBody ? bodyAPtr->m_externalForceImpulse : btVector3(0,0,0); - btVector3 externalTorqueImpulseA = bodyAPtr->m_originalBody ? bodyAPtr->m_externalTorqueImpulse : btVector3(0,0,0); - - btVector3 externalForceImpulseB = bodyBPtr->m_originalBody ? bodyBPtr->m_externalForceImpulse : btVector3(0,0,0); - btVector3 externalTorqueImpulseB = bodyBPtr->m_originalBody ?bodyBPtr->m_externalTorqueImpulse : btVector3(0,0,0); - - btScalar vel1Dotn = solverConstraint.m_contactNormal1.dot(rbA.getLinearVelocity()+externalForceImpulseA) - + solverConstraint.m_relpos1CrossNormal.dot(rbA.getAngularVelocity()+externalTorqueImpulseA); - - btScalar vel2Dotn = solverConstraint.m_contactNormal2.dot(rbB.getLinearVelocity()+externalForceImpulseB) - + solverConstraint.m_relpos2CrossNormal.dot(rbB.getAngularVelocity()+externalTorqueImpulseB); - - rel_vel = vel1Dotn+vel2Dotn; - btScalar restitution = 0.f; - btScalar positionalError = solverConstraint.m_rhs;//already filled in by getConstraintInfo2 - btScalar velocityError = restitution - rel_vel * info2.m_damping; - btScalar penetrationImpulse = positionalError*solverConstraint.m_jacDiagABInv; - btScalar velocityImpulse = velocityError *solverConstraint.m_jacDiagABInv; - solverConstraint.m_rhs = penetrationImpulse+velocityImpulse; - solverConstraint.m_appliedImpulse = 0.f; - } - } -} - - -void btSequentialImpulseConstraintSolver::convertJoints(btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal) -{ - BT_PROFILE("convertJoints"); - for (int j=0;jbuildJacobian(); - constraint->internalSetAppliedImpulse(0.0f); - } - - int totalNumRows = 0; - - m_tmpConstraintSizesPool.resizeNoInitialize(numConstraints); - //calculate the total number of contraint rows - for (int i=0;igetJointFeedback(); - if (fb) - { - fb->m_appliedForceBodyA.setZero(); - fb->m_appliedTorqueBodyA.setZero(); - fb->m_appliedForceBodyB.setZero(); - fb->m_appliedTorqueBodyB.setZero(); - } - - if (constraints[i]->isEnabled()) - { - constraints[i]->getInfo1(&info1); - } else - { - info1.m_numConstraintRows = 0; - info1.nub = 0; - } - totalNumRows += info1.m_numConstraintRows; - } - m_tmpSolverNonContactConstraintPool.resizeNoInitialize(totalNumRows); - - - ///setup the btSolverConstraints - int currentRow = 0; - - for (int i=0;igetRigidBodyA(); - btRigidBody& rbB = constraint->getRigidBodyB(); - - int solverBodyIdA = getOrInitSolverBody(rbA,infoGlobal.m_timeStep); - int solverBodyIdB = getOrInitSolverBody(rbB,infoGlobal.m_timeStep); - - convertJoint(currentConstraintRow, constraint, info1, solverBodyIdA, solverBodyIdB, infoGlobal); - } - currentRow+=info1.m_numConstraintRows; - } -} - - -void btSequentialImpulseConstraintSolver::convertBodies(btCollisionObject** bodies, int numBodies, const btContactSolverInfo& infoGlobal) -{ - BT_PROFILE("convertBodies"); - for (int i = 0; i < numBodies; i++) - { - bodies[i]->setCompanionId(-1); - } -#if BT_THREADSAFE - m_kinematicBodyUniqueIdToSolverBodyTable.resize( 0 ); -#endif // BT_THREADSAFE - - m_tmpSolverBodyPool.reserve(numBodies+1); - m_tmpSolverBodyPool.resize(0); - - //btSolverBody& fixedBody = m_tmpSolverBodyPool.expand(); - //initSolverBody(&fixedBody,0); - - for (int i=0;igetInvMass()) - { - btSolverBody& solverBody = m_tmpSolverBodyPool[bodyId]; - btVector3 gyroForce (0,0,0); - if (body->getFlags()&BT_ENABLE_GYROSCOPIC_FORCE_EXPLICIT) - { - gyroForce = body->computeGyroscopicForceExplicit(infoGlobal.m_maxGyroscopicForce); - solverBody.m_externalTorqueImpulse -= gyroForce*body->getInvInertiaTensorWorld()*infoGlobal.m_timeStep; - } - if (body->getFlags()&BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_WORLD) - { - gyroForce = body->computeGyroscopicImpulseImplicit_World(infoGlobal.m_timeStep); - solverBody.m_externalTorqueImpulse += gyroForce; - } - if (body->getFlags()&BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_BODY) - { - gyroForce = body->computeGyroscopicImpulseImplicit_Body(infoGlobal.m_timeStep); - solverBody.m_externalTorqueImpulse += gyroForce; - - } - } - } -} - - btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySetup(btCollisionObject** bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer) { m_fixedBodyId = -1; @@ -1603,14 +1344,254 @@ btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySetup(btCol #endif //BT_ADDITIONAL_DEBUG + for (int i = 0; i < numBodies; i++) + { + bodies[i]->setCompanionId(-1); + } +#if BT_THREADSAFE + m_kinematicBodyUniqueIdToSolverBodyTable.resize( 0 ); +#endif // BT_THREADSAFE + + m_tmpSolverBodyPool.reserve(numBodies+1); + m_tmpSolverBodyPool.resize(0); + + //btSolverBody& fixedBody = m_tmpSolverBodyPool.expand(); + //initSolverBody(&fixedBody,0); + //convert all bodies - convertBodies(bodies, numBodies, infoGlobal); - convertJoints(constraints, numConstraints, infoGlobal); - convertContacts(manifoldPtr,numManifolds,infoGlobal); + for (int i=0;igetInvMass()) + { + btSolverBody& solverBody = m_tmpSolverBodyPool[bodyId]; + btVector3 gyroForce (0,0,0); + if (body->getFlags()&BT_ENABLE_GYROSCOPIC_FORCE_EXPLICIT) + { + gyroForce = body->computeGyroscopicForceExplicit(infoGlobal.m_maxGyroscopicForce); + solverBody.m_externalTorqueImpulse -= gyroForce*body->getInvInertiaTensorWorld()*infoGlobal.m_timeStep; + } + if (body->getFlags()&BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_WORLD) + { + gyroForce = body->computeGyroscopicImpulseImplicit_World(infoGlobal.m_timeStep); + solverBody.m_externalTorqueImpulse += gyroForce; + } + if (body->getFlags()&BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_BODY) + { + gyroForce = body->computeGyroscopicImpulseImplicit_Body(infoGlobal.m_timeStep); + solverBody.m_externalTorqueImpulse += gyroForce; + + } + + + } + } + + if (1) + { + int j; + for (j=0;jbuildJacobian(); + constraint->internalSetAppliedImpulse(0.0f); + } + } + + //btRigidBody* rb0=0,*rb1=0; + + //if (1) + { + { + + int totalNumRows = 0; + int i; + + m_tmpConstraintSizesPool.resizeNoInitialize(numConstraints); + //calculate the total number of contraint rows + for (i=0;igetJointFeedback(); + if (fb) + { + fb->m_appliedForceBodyA.setZero(); + fb->m_appliedTorqueBodyA.setZero(); + fb->m_appliedForceBodyB.setZero(); + fb->m_appliedTorqueBodyB.setZero(); + } + + if (constraints[i]->isEnabled()) + { + } + if (constraints[i]->isEnabled()) + { + constraints[i]->getInfo1(&info1); + } else + { + info1.m_numConstraintRows = 0; + info1.nub = 0; + } + totalNumRows += info1.m_numConstraintRows; + } + m_tmpSolverNonContactConstraintPool.resizeNoInitialize(totalNumRows); + + + ///setup the btSolverConstraints + int currentRow = 0; + + for (i=0;igetRigidBodyA(); + btRigidBody& rbB = constraint->getRigidBodyB(); + + int solverBodyIdA = getOrInitSolverBody(rbA,infoGlobal.m_timeStep); + int solverBodyIdB = getOrInitSolverBody(rbB,infoGlobal.m_timeStep); + + btSolverBody* bodyAPtr = &m_tmpSolverBodyPool[solverBodyIdA]; + btSolverBody* bodyBPtr = &m_tmpSolverBodyPool[solverBodyIdB]; + + + int overrideNumSolverIterations = constraint->getOverrideNumSolverIterations() > 0 ? constraint->getOverrideNumSolverIterations() : infoGlobal.m_numIterations; + if (overrideNumSolverIterations>m_maxOverrideNumSolverIterations) + m_maxOverrideNumSolverIterations = overrideNumSolverIterations; + + + int j; + for ( j=0;jinternalGetDeltaLinearVelocity().setValue(0.f,0.f,0.f); + bodyAPtr->internalGetDeltaAngularVelocity().setValue(0.f,0.f,0.f); + bodyAPtr->internalGetPushVelocity().setValue(0.f,0.f,0.f); + bodyAPtr->internalGetTurnVelocity().setValue(0.f,0.f,0.f); + bodyBPtr->internalGetDeltaLinearVelocity().setValue(0.f,0.f,0.f); + bodyBPtr->internalGetDeltaAngularVelocity().setValue(0.f,0.f,0.f); + bodyBPtr->internalGetPushVelocity().setValue(0.f,0.f,0.f); + bodyBPtr->internalGetTurnVelocity().setValue(0.f,0.f,0.f); + + + btTypedConstraint::btConstraintInfo2 info2; + info2.fps = 1.f/infoGlobal.m_timeStep; + info2.erp = infoGlobal.m_erp; + info2.m_J1linearAxis = currentConstraintRow->m_contactNormal1; + info2.m_J1angularAxis = currentConstraintRow->m_relpos1CrossNormal; + info2.m_J2linearAxis = currentConstraintRow->m_contactNormal2; + info2.m_J2angularAxis = currentConstraintRow->m_relpos2CrossNormal; + info2.rowskip = sizeof(btSolverConstraint)/sizeof(btScalar);//check this + ///the size of btSolverConstraint needs be a multiple of btScalar + btAssert(info2.rowskip*sizeof(btScalar)== sizeof(btSolverConstraint)); + info2.m_constraintError = ¤tConstraintRow->m_rhs; + currentConstraintRow->m_cfm = infoGlobal.m_globalCfm; + info2.m_damping = infoGlobal.m_damping; + info2.cfm = ¤tConstraintRow->m_cfm; + info2.m_lowerLimit = ¤tConstraintRow->m_lowerLimit; + info2.m_upperLimit = ¤tConstraintRow->m_upperLimit; + info2.m_numIterations = infoGlobal.m_numIterations; + constraints[i]->getInfo2(&info2); + + ///finalize the constraint setup + for ( j=0;j=constraints[i]->getBreakingImpulseThreshold()) + { + solverConstraint.m_upperLimit = constraints[i]->getBreakingImpulseThreshold(); + } + + if (solverConstraint.m_lowerLimit<=-constraints[i]->getBreakingImpulseThreshold()) + { + solverConstraint.m_lowerLimit = -constraints[i]->getBreakingImpulseThreshold(); + } + + solverConstraint.m_originalContactPoint = constraint; + + { + const btVector3& ftorqueAxis1 = solverConstraint.m_relpos1CrossNormal; + solverConstraint.m_angularComponentA = constraint->getRigidBodyA().getInvInertiaTensorWorld()*ftorqueAxis1*constraint->getRigidBodyA().getAngularFactor(); + } + { + const btVector3& ftorqueAxis2 = solverConstraint.m_relpos2CrossNormal; + solverConstraint.m_angularComponentB = constraint->getRigidBodyB().getInvInertiaTensorWorld()*ftorqueAxis2*constraint->getRigidBodyB().getAngularFactor(); + } + + { + btVector3 iMJlA = solverConstraint.m_contactNormal1*rbA.getInvMass(); + btVector3 iMJaA = rbA.getInvInertiaTensorWorld()*solverConstraint.m_relpos1CrossNormal; + btVector3 iMJlB = solverConstraint.m_contactNormal2*rbB.getInvMass();//sign of normal? + btVector3 iMJaB = rbB.getInvInertiaTensorWorld()*solverConstraint.m_relpos2CrossNormal; + + btScalar sum = iMJlA.dot(solverConstraint.m_contactNormal1); + sum += iMJaA.dot(solverConstraint.m_relpos1CrossNormal); + sum += iMJlB.dot(solverConstraint.m_contactNormal2); + sum += iMJaB.dot(solverConstraint.m_relpos2CrossNormal); + btScalar fsum = btFabs(sum); + btAssert(fsum > SIMD_EPSILON); + btScalar sorRelaxation = 1.f;//todo: get from globalInfo? + solverConstraint.m_jacDiagABInv = fsum>SIMD_EPSILON?sorRelaxation/sum : 0.f; + } + + + + { + btScalar rel_vel; + btVector3 externalForceImpulseA = bodyAPtr->m_originalBody ? bodyAPtr->m_externalForceImpulse : btVector3(0,0,0); + btVector3 externalTorqueImpulseA = bodyAPtr->m_originalBody ? bodyAPtr->m_externalTorqueImpulse : btVector3(0,0,0); + + btVector3 externalForceImpulseB = bodyBPtr->m_originalBody ? bodyBPtr->m_externalForceImpulse : btVector3(0,0,0); + btVector3 externalTorqueImpulseB = bodyBPtr->m_originalBody ?bodyBPtr->m_externalTorqueImpulse : btVector3(0,0,0); + + btScalar vel1Dotn = solverConstraint.m_contactNormal1.dot(rbA.getLinearVelocity()+externalForceImpulseA) + + solverConstraint.m_relpos1CrossNormal.dot(rbA.getAngularVelocity()+externalTorqueImpulseA); + + btScalar vel2Dotn = solverConstraint.m_contactNormal2.dot(rbB.getLinearVelocity()+externalForceImpulseB) + + solverConstraint.m_relpos2CrossNormal.dot(rbB.getAngularVelocity()+externalTorqueImpulseB); + + rel_vel = vel1Dotn+vel2Dotn; + btScalar restitution = 0.f; + btScalar positionalError = solverConstraint.m_rhs;//already filled in by getConstraintInfo2 + btScalar velocityError = restitution - rel_vel * info2.m_damping; + btScalar penetrationImpulse = positionalError*solverConstraint.m_jacDiagABInv; + btScalar velocityImpulse = velocityError *solverConstraint.m_jacDiagABInv; + solverConstraint.m_rhs = penetrationImpulse+velocityImpulse; + solverConstraint.m_appliedImpulse = 0.f; + + + } + } + } + currentRow+=m_tmpConstraintSizesPool[i].m_numConstraintRows; + } + } + + convertContacts(manifoldPtr,numManifolds,infoGlobal); + + } + // btContactSolverInfo info = infoGlobal; @@ -1649,7 +1630,6 @@ btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySetup(btCol btScalar btSequentialImpulseConstraintSolver::solveSingleIteration(int iteration, btCollisionObject** /*bodies */,int /*numBodies*/,btPersistentManifold** /*manifoldPtr*/, int /*numManifolds*/,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* /*debugDrawer*/) { - BT_PROFILE("solveSingleIteration"); btScalar leastSquaresResidual = 0.f; int numNonContactPool = m_tmpSolverNonContactConstraintPool.size(); @@ -1695,7 +1675,7 @@ btScalar btSequentialImpulseConstraintSolver::solveSingleIteration(int iteration if (iteration < constraint.m_overrideNumSolverIterations) { btScalar residual = resolveSingleConstraintRowGeneric(m_tmpSolverBodyPool[constraint.m_solverBodyIdA],m_tmpSolverBodyPool[constraint.m_solverBodyIdB],constraint); - leastSquaresResidual = btMax(leastSquaresResidual, residual*residual); + leastSquaresResidual += residual*residual; } } @@ -1726,7 +1706,7 @@ btScalar btSequentialImpulseConstraintSolver::solveSingleIteration(int iteration { const btSolverConstraint& solveManifold = m_tmpSolverContactConstraintPool[m_orderTmpConstraintPool[c]]; btScalar residual = resolveSingleConstraintRowLowerLimit(m_tmpSolverBodyPool[solveManifold.m_solverBodyIdA],m_tmpSolverBodyPool[solveManifold.m_solverBodyIdB],solveManifold); - leastSquaresResidual = btMax(leastSquaresResidual, residual*residual); + leastSquaresResidual += residual*residual; totalImpulse = solveManifold.m_appliedImpulse; } @@ -1743,7 +1723,7 @@ btScalar btSequentialImpulseConstraintSolver::solveSingleIteration(int iteration solveManifold.m_upperLimit = solveManifold.m_friction*totalImpulse; btScalar residual = resolveSingleConstraintRowGeneric(m_tmpSolverBodyPool[solveManifold.m_solverBodyIdA],m_tmpSolverBodyPool[solveManifold.m_solverBodyIdB],solveManifold); - leastSquaresResidual = btMax(leastSquaresResidual, residual*residual); + leastSquaresResidual += residual*residual; } } @@ -1758,7 +1738,7 @@ btScalar btSequentialImpulseConstraintSolver::solveSingleIteration(int iteration solveManifold.m_upperLimit = solveManifold.m_friction*totalImpulse; btScalar residual = resolveSingleConstraintRowGeneric(m_tmpSolverBodyPool[solveManifold.m_solverBodyIdA],m_tmpSolverBodyPool[solveManifold.m_solverBodyIdB],solveManifold); - leastSquaresResidual = btMax(leastSquaresResidual, residual*residual); + leastSquaresResidual += residual*residual; } } } @@ -1775,7 +1755,7 @@ btScalar btSequentialImpulseConstraintSolver::solveSingleIteration(int iteration { const btSolverConstraint& solveManifold = m_tmpSolverContactConstraintPool[m_orderTmpConstraintPool[j]]; btScalar residual = resolveSingleConstraintRowLowerLimit(m_tmpSolverBodyPool[solveManifold.m_solverBodyIdA],m_tmpSolverBodyPool[solveManifold.m_solverBodyIdB],solveManifold); - leastSquaresResidual = btMax(leastSquaresResidual, residual*residual); + leastSquaresResidual += residual*residual; } @@ -1794,7 +1774,7 @@ btScalar btSequentialImpulseConstraintSolver::solveSingleIteration(int iteration solveManifold.m_upperLimit = solveManifold.m_friction*totalImpulse; btScalar residual = resolveSingleConstraintRowGeneric(m_tmpSolverBodyPool[solveManifold.m_solverBodyIdA],m_tmpSolverBodyPool[solveManifold.m_solverBodyIdB],solveManifold); - leastSquaresResidual = btMax(leastSquaresResidual, residual*residual); + leastSquaresResidual += residual*residual; } } } @@ -1816,7 +1796,7 @@ btScalar btSequentialImpulseConstraintSolver::solveSingleIteration(int iteration rollingFrictionConstraint.m_upperLimit = rollingFrictionMagnitude; btScalar residual = resolveSingleConstraintRowGeneric(m_tmpSolverBodyPool[rollingFrictionConstraint.m_solverBodyIdA],m_tmpSolverBodyPool[rollingFrictionConstraint.m_solverBodyIdB],rollingFrictionConstraint); - leastSquaresResidual = btMax(leastSquaresResidual, residual*residual); + leastSquaresResidual += residual*residual; } } @@ -1828,7 +1808,6 @@ btScalar btSequentialImpulseConstraintSolver::solveSingleIteration(int iteration void btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySplitImpulseIterations(btCollisionObject** bodies,int numBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer) { - BT_PROFILE("solveGroupCacheFriendlySplitImpulseIterations"); int iteration; if (infoGlobal.m_splitImpulse) { @@ -1844,7 +1823,7 @@ void btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySplitImpulseIte const btSolverConstraint& solveManifold = m_tmpSolverContactConstraintPool[m_orderTmpConstraintPool[j]]; btScalar residual = resolveSplitPenetrationImpulse(m_tmpSolverBodyPool[solveManifold.m_solverBodyIdA],m_tmpSolverBodyPool[solveManifold.m_solverBodyIdB],solveManifold); - leastSquaresResidual = btMax(leastSquaresResidual, residual*residual); + leastSquaresResidual += residual*residual; } } if (leastSquaresResidual <= infoGlobal.m_leastSquaresResidualThreshold || iteration>=(infoGlobal.m_numIterations-1)) @@ -1887,9 +1866,14 @@ btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlyIterations( return 0.f; } -void btSequentialImpulseConstraintSolver::writeBackContacts(int iBegin, int iEnd, const btContactSolverInfo& infoGlobal) +btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlyFinish(btCollisionObject** bodies,int numBodies,const btContactSolverInfo& infoGlobal) { - for (int j=iBegin; jsetEnabled(false); } } -} -void btSequentialImpulseConstraintSolver::writeBackBodies(int iBegin, int iEnd, const btContactSolverInfo& infoGlobal) -{ - for (int i=iBegin; isetCompanionId(-1); } } -} - -btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlyFinish(btCollisionObject** bodies,int numBodies,const btContactSolverInfo& infoGlobal) -{ - BT_PROFILE("solveGroupCacheFriendlyFinish"); - - if (infoGlobal.m_solverMode & SOLVER_USE_WARMSTARTING) - { - writeBackContacts(0, m_tmpSolverContactConstraintPool.size(), infoGlobal); - } - - writeBackJoints(0, m_tmpSolverNonContactConstraintPool.size(), infoGlobal); - writeBackBodies(0, m_tmpSolverBodyPool.size(), infoGlobal); m_tmpSolverContactConstraintPool.resizeNoInitialize(0); m_tmpSolverNonContactConstraintPool.resizeNoInitialize(0); diff --git a/extern/bullet/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h b/extern/bullet/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h index b834c3dac3be..16c7eb74c1de 100644 --- a/extern/bullet/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h +++ b/extern/bullet/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h @@ -4,8 +4,8 @@ Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, subject to the following restrictions: 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. @@ -27,7 +27,7 @@ class btCollisionObject; #include "BulletCollision/NarrowPhaseCollision/btManifoldPoint.h" #include "BulletDynamics/ConstraintSolver/btConstraintSolver.h" -typedef btScalar(*btSingleConstraintRowSolver)(btSolverBody&, btSolverBody&, const btSolverConstraint&); +typedef btSimdScalar(*btSingleConstraintRowSolver)(btSolverBody&, btSolverBody&, const btSolverConstraint&); ///The btSequentialImpulseConstraintSolver is a fast SIMD implementation of the Projected Gauss Seidel (iterative LCP) method. ATTRIBUTE_ALIGNED16(class) btSequentialImpulseConstraintSolver : public btConstraintSolver @@ -64,48 +64,44 @@ ATTRIBUTE_ALIGNED16(class) btSequentialImpulseConstraintSolver : public btConstr void setupFrictionConstraint( btSolverConstraint& solverConstraint, const btVector3& normalAxis,int solverBodyIdA,int solverBodyIdB, btManifoldPoint& cp,const btVector3& rel_pos1,const btVector3& rel_pos2, - btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, + btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity=0., btScalar cfmSlip=0.); void setupTorsionalFrictionConstraint( btSolverConstraint& solverConstraint, const btVector3& normalAxis,int solverBodyIdA,int solverBodyIdB, btManifoldPoint& cp,btScalar combinedTorsionalFriction, const btVector3& rel_pos1,const btVector3& rel_pos2, - btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, + btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, btScalar desiredVelocity=0., btScalar cfmSlip=0.); btSolverConstraint& addFrictionConstraint(const btVector3& normalAxis,int solverBodyIdA,int solverBodyIdB,int frictionIndex,btManifoldPoint& cp,const btVector3& rel_pos1,const btVector3& rel_pos2,btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity=0., btScalar cfmSlip=0.); btSolverConstraint& addTorsionalFrictionConstraint(const btVector3& normalAxis,int solverBodyIdA,int solverBodyIdB,int frictionIndex,btManifoldPoint& cp,btScalar torsionalFriction, const btVector3& rel_pos1,const btVector3& rel_pos2,btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, btScalar desiredVelocity=0, btScalar cfmSlip=0.f); - - void setupContactConstraint(btSolverConstraint& solverConstraint, int solverBodyIdA, int solverBodyIdB, btManifoldPoint& cp, + + void setupContactConstraint(btSolverConstraint& solverConstraint, int solverBodyIdA, int solverBodyIdB, btManifoldPoint& cp, const btContactSolverInfo& infoGlobal,btScalar& relaxation, const btVector3& rel_pos1, const btVector3& rel_pos2); static void applyAnisotropicFriction(btCollisionObject* colObj,btVector3& frictionDirection, int frictionMode); - void setFrictionConstraintImpulse( btSolverConstraint& solverConstraint, int solverBodyIdA,int solverBodyIdB, + void setFrictionConstraintImpulse( btSolverConstraint& solverConstraint, int solverBodyIdA,int solverBodyIdB, btManifoldPoint& cp, const btContactSolverInfo& infoGlobal); ///m_btSeed2 is used for re-arranging the constraint rows. improves convergence/quality of friction unsigned long m_btSeed2; - + btScalar restitutionCurve(btScalar rel_vel, btScalar restitution, btScalar velocityThreshold); virtual void convertContacts(btPersistentManifold** manifoldPtr, int numManifolds, const btContactSolverInfo& infoGlobal); void convertContact(btPersistentManifold* manifold,const btContactSolverInfo& infoGlobal); - virtual void convertJoints(btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal); - void convertJoint(btSolverConstraint* currentConstraintRow, btTypedConstraint* constraint, const btTypedConstraint::btConstraintInfo1& info1, int solverBodyIdA, int solverBodyIdB, const btContactSolverInfo& infoGlobal); - - virtual void convertBodies(btCollisionObject** bodies, int numBodies, const btContactSolverInfo& infoGlobal); - btScalar resolveSplitPenetrationSIMD(btSolverBody& bodyA,btSolverBody& bodyB, const btSolverConstraint& contactConstraint) + btSimdScalar resolveSplitPenetrationSIMD(btSolverBody& bodyA,btSolverBody& bodyB, const btSolverConstraint& contactConstraint) { return m_resolveSplitPenetrationImpulse( bodyA, bodyB, contactConstraint ); } - btScalar resolveSplitPenetrationImpulseCacheFriendly(btSolverBody& bodyA,btSolverBody& bodyB, const btSolverConstraint& contactConstraint) + btSimdScalar resolveSplitPenetrationImpulseCacheFriendly(btSolverBody& bodyA,btSolverBody& bodyB, const btSolverConstraint& contactConstraint) { return m_resolveSplitPenetrationImpulse( bodyA, bodyB, contactConstraint ); } @@ -114,20 +110,18 @@ ATTRIBUTE_ALIGNED16(class) btSequentialImpulseConstraintSolver : public btConstr int getOrInitSolverBody(btCollisionObject& body,btScalar timeStep); void initSolverBody(btSolverBody* solverBody, btCollisionObject* collisionObject, btScalar timeStep); - btScalar resolveSingleConstraintRowGeneric(btSolverBody& bodyA,btSolverBody& bodyB,const btSolverConstraint& contactConstraint); - btScalar resolveSingleConstraintRowGenericSIMD(btSolverBody& bodyA,btSolverBody& bodyB,const btSolverConstraint& contactConstraint); - btScalar resolveSingleConstraintRowLowerLimit(btSolverBody& bodyA,btSolverBody& bodyB,const btSolverConstraint& contactConstraint); - btScalar resolveSingleConstraintRowLowerLimitSIMD(btSolverBody& bodyA,btSolverBody& bodyB,const btSolverConstraint& contactConstraint); - btScalar resolveSplitPenetrationImpulse(btSolverBody& bodyA,btSolverBody& bodyB, const btSolverConstraint& contactConstraint) + btSimdScalar resolveSingleConstraintRowGeneric(btSolverBody& bodyA,btSolverBody& bodyB,const btSolverConstraint& contactConstraint); + btSimdScalar resolveSingleConstraintRowGenericSIMD(btSolverBody& bodyA,btSolverBody& bodyB,const btSolverConstraint& contactConstraint); + btSimdScalar resolveSingleConstraintRowLowerLimit(btSolverBody& bodyA,btSolverBody& bodyB,const btSolverConstraint& contactConstraint); + btSimdScalar resolveSingleConstraintRowLowerLimitSIMD(btSolverBody& bodyA,btSolverBody& bodyB,const btSolverConstraint& contactConstraint); + btSimdScalar resolveSplitPenetrationImpulse(btSolverBody& bodyA,btSolverBody& bodyB, const btSolverConstraint& contactConstraint) { return m_resolveSplitPenetrationImpulse( bodyA, bodyB, contactConstraint ); } - + protected: - - void writeBackContacts(int iBegin, int iEnd, const btContactSolverInfo& infoGlobal); - void writeBackJoints(int iBegin, int iEnd, const btContactSolverInfo& infoGlobal); - void writeBackBodies(int iBegin, int iEnd, const btContactSolverInfo& infoGlobal); + + virtual void solveGroupCacheFriendlySplitImpulseIterations(btCollisionObject** bodies,int numBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer); virtual btScalar solveGroupCacheFriendlyFinish(btCollisionObject** bodies,int numBodies,const btContactSolverInfo& infoGlobal); virtual btScalar solveSingleIteration(int iteration, btCollisionObject** bodies ,int numBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer); @@ -139,15 +133,15 @@ ATTRIBUTE_ALIGNED16(class) btSequentialImpulseConstraintSolver : public btConstr public: BT_DECLARE_ALIGNED_ALLOCATOR(); - + btSequentialImpulseConstraintSolver(); virtual ~btSequentialImpulseConstraintSolver(); virtual btScalar solveGroup(btCollisionObject** bodies,int numBodies,btPersistentManifold** manifold,int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& info, btIDebugDraw* debugDrawer,btDispatcher* dispatcher); - + ///clear internal cached data and reset random seed virtual void reset(); - + unsigned long btRand2(); int btRandInt2 (int n); @@ -161,7 +155,7 @@ ATTRIBUTE_ALIGNED16(class) btSequentialImpulseConstraintSolver : public btConstr return m_btSeed2; } - + virtual btConstraintSolverType getSolverType() const { return BT_SEQUENTIAL_IMPULSE_SOLVER; diff --git a/extern/bullet/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.cpp b/extern/bullet/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.cpp deleted file mode 100644 index 4306c37e495a..000000000000 --- a/extern/bullet/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.cpp +++ /dev/null @@ -1,1621 +0,0 @@ -/* -Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - - -#include "btSequentialImpulseConstraintSolverMt.h" - -#include "LinearMath/btQuickprof.h" - -#include "BulletCollision/NarrowPhaseCollision/btPersistentManifold.h" - -#include "BulletDynamics/ConstraintSolver/btTypedConstraint.h" -#include "BulletDynamics/Dynamics/btRigidBody.h" - - - -bool btSequentialImpulseConstraintSolverMt::s_allowNestedParallelForLoops = false; // some task schedulers don't like nested loops -int btSequentialImpulseConstraintSolverMt::s_minimumContactManifoldsForBatching = 250; -int btSequentialImpulseConstraintSolverMt::s_minBatchSize = 50; -int btSequentialImpulseConstraintSolverMt::s_maxBatchSize = 100; -btBatchedConstraints::BatchingMethod btSequentialImpulseConstraintSolverMt::s_contactBatchingMethod = btBatchedConstraints::BATCHING_METHOD_SPATIAL_GRID_2D; -btBatchedConstraints::BatchingMethod btSequentialImpulseConstraintSolverMt::s_jointBatchingMethod = btBatchedConstraints::BATCHING_METHOD_SPATIAL_GRID_2D; - - -btSequentialImpulseConstraintSolverMt::btSequentialImpulseConstraintSolverMt() -{ - m_numFrictionDirections = 1; - m_useBatching = false; - m_useObsoleteJointConstraints = false; -} - - -btSequentialImpulseConstraintSolverMt::~btSequentialImpulseConstraintSolverMt() -{ -} - - -void btSequentialImpulseConstraintSolverMt::setupBatchedContactConstraints() -{ - BT_PROFILE("setupBatchedContactConstraints"); - m_batchedContactConstraints.setup( &m_tmpSolverContactConstraintPool, - m_tmpSolverBodyPool, - s_contactBatchingMethod, - s_minBatchSize, - s_maxBatchSize, - &m_scratchMemory - ); -} - - -void btSequentialImpulseConstraintSolverMt::setupBatchedJointConstraints() -{ - BT_PROFILE("setupBatchedJointConstraints"); - m_batchedJointConstraints.setup( &m_tmpSolverNonContactConstraintPool, - m_tmpSolverBodyPool, - s_jointBatchingMethod, - s_minBatchSize, - s_maxBatchSize, - &m_scratchMemory - ); -} - - -void btSequentialImpulseConstraintSolverMt::internalSetupContactConstraints(int iContactConstraint, const btContactSolverInfo& infoGlobal) -{ - btSolverConstraint& contactConstraint = m_tmpSolverContactConstraintPool[iContactConstraint]; - - btVector3 rel_pos1; - btVector3 rel_pos2; - btScalar relaxation; - - int solverBodyIdA = contactConstraint.m_solverBodyIdA; - int solverBodyIdB = contactConstraint.m_solverBodyIdB; - - btSolverBody* solverBodyA = &m_tmpSolverBodyPool[ solverBodyIdA ]; - btSolverBody* solverBodyB = &m_tmpSolverBodyPool[ solverBodyIdB ]; - - btRigidBody* colObj0 = solverBodyA->m_originalBody; - btRigidBody* colObj1 = solverBodyB->m_originalBody; - - btManifoldPoint& cp = *static_cast( contactConstraint.m_originalContactPoint ); - - const btVector3& pos1 = cp.getPositionWorldOnA(); - const btVector3& pos2 = cp.getPositionWorldOnB(); - - rel_pos1 = pos1 - solverBodyA->getWorldTransform().getOrigin(); - rel_pos2 = pos2 - solverBodyB->getWorldTransform().getOrigin(); - - btVector3 vel1; - btVector3 vel2; - - solverBodyA->getVelocityInLocalPointNoDelta( rel_pos1, vel1 ); - solverBodyB->getVelocityInLocalPointNoDelta( rel_pos2, vel2 ); - - btVector3 vel = vel1 - vel2; - btScalar rel_vel = cp.m_normalWorldOnB.dot( vel ); - - setupContactConstraint( contactConstraint, solverBodyIdA, solverBodyIdB, cp, infoGlobal, relaxation, rel_pos1, rel_pos2 ); - - // setup rolling friction constraints - int rollingFrictionIndex = m_rollingFrictionIndexTable[iContactConstraint]; - if (rollingFrictionIndex >= 0) - { - btSolverConstraint& spinningFrictionConstraint = m_tmpSolverContactRollingFrictionConstraintPool[ rollingFrictionIndex ]; - btAssert( spinningFrictionConstraint.m_frictionIndex == iContactConstraint ); - setupTorsionalFrictionConstraint( spinningFrictionConstraint, - cp.m_normalWorldOnB, - solverBodyIdA, - solverBodyIdB, - cp, - cp.m_combinedSpinningFriction, - rel_pos1, - rel_pos2, - colObj0, - colObj1, - relaxation, - 0.0f, - 0.0f - ); - btVector3 axis[2]; - btPlaneSpace1( cp.m_normalWorldOnB, axis[0], axis[1] ); - axis[0].normalize(); - axis[1].normalize(); - - applyAnisotropicFriction( colObj0, axis[0], btCollisionObject::CF_ANISOTROPIC_ROLLING_FRICTION ); - applyAnisotropicFriction( colObj1, axis[0], btCollisionObject::CF_ANISOTROPIC_ROLLING_FRICTION ); - applyAnisotropicFriction( colObj0, axis[1], btCollisionObject::CF_ANISOTROPIC_ROLLING_FRICTION ); - applyAnisotropicFriction( colObj1, axis[1], btCollisionObject::CF_ANISOTROPIC_ROLLING_FRICTION ); - // put the largest axis first - if (axis[1].length2() > axis[0].length2()) - { - btSwap(axis[0], axis[1]); - } - const btScalar kRollingFrictionThreshold = 0.001f; - for (int i = 0; i < 2; ++i) - { - int iRollingFric = rollingFrictionIndex + 1 + i; - btSolverConstraint& rollingFrictionConstraint = m_tmpSolverContactRollingFrictionConstraintPool[ iRollingFric ]; - btAssert(rollingFrictionConstraint.m_frictionIndex == iContactConstraint); - btVector3 dir = axis[i]; - if ( dir.length() > kRollingFrictionThreshold ) - { - setupTorsionalFrictionConstraint( rollingFrictionConstraint, - dir, - solverBodyIdA, - solverBodyIdB, - cp, - cp.m_combinedRollingFriction, - rel_pos1, - rel_pos2, - colObj0, - colObj1, - relaxation, - 0.0f, - 0.0f - ); - } - else - { - rollingFrictionConstraint.m_frictionIndex = -1; // disable constraint - } - } - } - - // setup friction constraints - // setupFrictionConstraint(solverConstraint, normalAxis, solverBodyIdA, solverBodyIdB, cp, rel_pos1, rel_pos2, colObj0, colObj1, relaxation, infoGlobal, desiredVelocity, cfmSlip); - { - ///Bullet has several options to set the friction directions - ///By default, each contact has only a single friction direction that is recomputed automatically very frame - ///based on the relative linear velocity. - ///If the relative velocity it zero, it will automatically compute a friction direction. - - ///You can also enable two friction directions, using the SOLVER_USE_2_FRICTION_DIRECTIONS. - ///In that case, the second friction direction will be orthogonal to both contact normal and first friction direction. - /// - ///If you choose SOLVER_DISABLE_VELOCITY_DEPENDENT_FRICTION_DIRECTION, then the friction will be independent from the relative projected velocity. - /// - ///The user can manually override the friction directions for certain contacts using a contact callback, - ///and set the cp.m_lateralFrictionInitialized to true - ///In that case, you can set the target relative motion in each friction direction (cp.m_contactMotion1 and cp.m_contactMotion2) - ///this will give a conveyor belt effect - /// - btSolverConstraint* frictionConstraint1 = &m_tmpSolverContactFrictionConstraintPool[contactConstraint.m_frictionIndex]; - btAssert(frictionConstraint1->m_frictionIndex == iContactConstraint); - - btSolverConstraint* frictionConstraint2 = NULL; - if ( infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS ) - { - frictionConstraint2 = &m_tmpSolverContactFrictionConstraintPool[contactConstraint.m_frictionIndex + 1]; - btAssert( frictionConstraint2->m_frictionIndex == iContactConstraint ); - } - - if ( !( infoGlobal.m_solverMode & SOLVER_ENABLE_FRICTION_DIRECTION_CACHING ) || !( cp.m_contactPointFlags&BT_CONTACT_FLAG_LATERAL_FRICTION_INITIALIZED ) ) - { - cp.m_lateralFrictionDir1 = vel - cp.m_normalWorldOnB * rel_vel; - btScalar lat_rel_vel = cp.m_lateralFrictionDir1.length2(); - if ( !( infoGlobal.m_solverMode & SOLVER_DISABLE_VELOCITY_DEPENDENT_FRICTION_DIRECTION ) && lat_rel_vel > SIMD_EPSILON ) - { - cp.m_lateralFrictionDir1 *= 1.f / btSqrt( lat_rel_vel ); - applyAnisotropicFriction( colObj0, cp.m_lateralFrictionDir1, btCollisionObject::CF_ANISOTROPIC_FRICTION ); - applyAnisotropicFriction( colObj1, cp.m_lateralFrictionDir1, btCollisionObject::CF_ANISOTROPIC_FRICTION ); - setupFrictionConstraint( *frictionConstraint1, cp.m_lateralFrictionDir1, solverBodyIdA, solverBodyIdB, cp, rel_pos1, rel_pos2, colObj0, colObj1, relaxation, infoGlobal ); - - if ( frictionConstraint2 ) - { - cp.m_lateralFrictionDir2 = cp.m_lateralFrictionDir1.cross( cp.m_normalWorldOnB ); - cp.m_lateralFrictionDir2.normalize();//?? - applyAnisotropicFriction( colObj0, cp.m_lateralFrictionDir2, btCollisionObject::CF_ANISOTROPIC_FRICTION ); - applyAnisotropicFriction( colObj1, cp.m_lateralFrictionDir2, btCollisionObject::CF_ANISOTROPIC_FRICTION ); - setupFrictionConstraint( *frictionConstraint2, cp.m_lateralFrictionDir2, solverBodyIdA, solverBodyIdB, cp, rel_pos1, rel_pos2, colObj0, colObj1, relaxation, infoGlobal ); - } - } - else - { - btPlaneSpace1( cp.m_normalWorldOnB, cp.m_lateralFrictionDir1, cp.m_lateralFrictionDir2 ); - - applyAnisotropicFriction( colObj0, cp.m_lateralFrictionDir1, btCollisionObject::CF_ANISOTROPIC_FRICTION ); - applyAnisotropicFriction( colObj1, cp.m_lateralFrictionDir1, btCollisionObject::CF_ANISOTROPIC_FRICTION ); - setupFrictionConstraint( *frictionConstraint1, cp.m_lateralFrictionDir1, solverBodyIdA, solverBodyIdB, cp, rel_pos1, rel_pos2, colObj0, colObj1, relaxation, infoGlobal ); - - if ( frictionConstraint2 ) - { - applyAnisotropicFriction( colObj0, cp.m_lateralFrictionDir2, btCollisionObject::CF_ANISOTROPIC_FRICTION ); - applyAnisotropicFriction( colObj1, cp.m_lateralFrictionDir2, btCollisionObject::CF_ANISOTROPIC_FRICTION ); - setupFrictionConstraint( *frictionConstraint2, cp.m_lateralFrictionDir2, solverBodyIdA, solverBodyIdB, cp, rel_pos1, rel_pos2, colObj0, colObj1, relaxation, infoGlobal ); - } - - if ( ( infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS ) && ( infoGlobal.m_solverMode & SOLVER_DISABLE_VELOCITY_DEPENDENT_FRICTION_DIRECTION ) ) - { - cp.m_contactPointFlags |= BT_CONTACT_FLAG_LATERAL_FRICTION_INITIALIZED; - } - } - } - else - { - setupFrictionConstraint( *frictionConstraint1, cp.m_lateralFrictionDir1, solverBodyIdA, solverBodyIdB, cp, rel_pos1, rel_pos2, colObj0, colObj1, relaxation, infoGlobal, cp.m_contactMotion1, cp.m_frictionCFM ); - if ( frictionConstraint2 ) - { - setupFrictionConstraint( *frictionConstraint2, cp.m_lateralFrictionDir2, solverBodyIdA, solverBodyIdB, cp, rel_pos1, rel_pos2, colObj0, colObj1, relaxation, infoGlobal, cp.m_contactMotion2, cp.m_frictionCFM ); - } - } - } - - setFrictionConstraintImpulse( contactConstraint, solverBodyIdA, solverBodyIdB, cp, infoGlobal ); -} - - -struct SetupContactConstraintsLoop : public btIParallelForBody -{ - btSequentialImpulseConstraintSolverMt* m_solver; - const btBatchedConstraints* m_bc; - const btContactSolverInfo* m_infoGlobal; - - SetupContactConstraintsLoop( btSequentialImpulseConstraintSolverMt* solver, const btBatchedConstraints* bc, const btContactSolverInfo& infoGlobal ) - { - m_solver = solver; - m_bc = bc; - m_infoGlobal = &infoGlobal; - } - void forLoop( int iBegin, int iEnd ) const BT_OVERRIDE - { - BT_PROFILE( "SetupContactConstraintsLoop" ); - for ( int iBatch = iBegin; iBatch < iEnd; ++iBatch ) - { - const btBatchedConstraints::Range& batch = m_bc->m_batches[ iBatch ]; - for (int i = batch.begin; i < batch.end; ++i) - { - int iContact = m_bc->m_constraintIndices[i]; - m_solver->internalSetupContactConstraints( iContact, *m_infoGlobal ); - } - } - } -}; - - -void btSequentialImpulseConstraintSolverMt::setupAllContactConstraints(const btContactSolverInfo& infoGlobal) -{ - BT_PROFILE( "setupAllContactConstraints" ); - if ( m_useBatching ) - { - const btBatchedConstraints& batchedCons = m_batchedContactConstraints; - SetupContactConstraintsLoop loop( this, &batchedCons, infoGlobal ); - for ( int iiPhase = 0; iiPhase < batchedCons.m_phases.size(); ++iiPhase ) - { - int iPhase = batchedCons.m_phaseOrder[ iiPhase ]; - const btBatchedConstraints::Range& phase = batchedCons.m_phases[ iPhase ]; - int grainSize = 1; - btParallelFor( phase.begin, phase.end, grainSize, loop ); - } - } - else - { - for ( int i = 0; i < m_tmpSolverContactConstraintPool.size(); ++i ) - { - internalSetupContactConstraints( i, infoGlobal ); - } - } -} - - -int btSequentialImpulseConstraintSolverMt::getOrInitSolverBodyThreadsafe(btCollisionObject& body,btScalar timeStep) -{ - // - // getOrInitSolverBody is threadsafe only for a single thread per solver (with potentially multiple solvers) - // - // getOrInitSolverBodyThreadsafe -- attempts to be fully threadsafe (however may affect determinism) - // - int solverBodyId = -1; - bool isRigidBodyType = btRigidBody::upcast( &body ) != NULL; - if ( isRigidBodyType && !body.isStaticOrKinematicObject() ) - { - // dynamic body - // Dynamic bodies can only be in one island, so it's safe to write to the companionId - solverBodyId = body.getCompanionId(); - if ( solverBodyId < 0 ) - { - m_bodySolverArrayMutex.lock(); - // now that we have the lock, check again - solverBodyId = body.getCompanionId(); - if ( solverBodyId < 0 ) - { - solverBodyId = m_tmpSolverBodyPool.size(); - btSolverBody& solverBody = m_tmpSolverBodyPool.expand(); - initSolverBody( &solverBody, &body, timeStep ); - body.setCompanionId( solverBodyId ); - } - m_bodySolverArrayMutex.unlock(); - } - } - else if (isRigidBodyType && body.isKinematicObject()) - { - // - // NOTE: must test for kinematic before static because some kinematic objects also - // identify as "static" - // - // Kinematic bodies can be in multiple islands at once, so it is a - // race condition to write to them, so we use an alternate method - // to record the solverBodyId - int uniqueId = body.getWorldArrayIndex(); - const int INVALID_SOLVER_BODY_ID = -1; - if (m_kinematicBodyUniqueIdToSolverBodyTable.size() <= uniqueId ) - { - m_kinematicBodyUniqueIdToSolverBodyTableMutex.lock(); - // now that we have the lock, check again - if ( m_kinematicBodyUniqueIdToSolverBodyTable.size() <= uniqueId ) - { - m_kinematicBodyUniqueIdToSolverBodyTable.resize( uniqueId + 1, INVALID_SOLVER_BODY_ID ); - } - m_kinematicBodyUniqueIdToSolverBodyTableMutex.unlock(); - } - solverBodyId = m_kinematicBodyUniqueIdToSolverBodyTable[ uniqueId ]; - // if no table entry yet, - if ( INVALID_SOLVER_BODY_ID == solverBodyId ) - { - // need to acquire both locks - m_kinematicBodyUniqueIdToSolverBodyTableMutex.lock(); - m_bodySolverArrayMutex.lock(); - // now that we have the lock, check again - solverBodyId = m_kinematicBodyUniqueIdToSolverBodyTable[ uniqueId ]; - if ( INVALID_SOLVER_BODY_ID == solverBodyId ) - { - // create a table entry for this body - solverBodyId = m_tmpSolverBodyPool.size(); - btSolverBody& solverBody = m_tmpSolverBodyPool.expand(); - initSolverBody( &solverBody, &body, timeStep ); - m_kinematicBodyUniqueIdToSolverBodyTable[ uniqueId ] = solverBodyId; - } - m_bodySolverArrayMutex.unlock(); - m_kinematicBodyUniqueIdToSolverBodyTableMutex.unlock(); - } - } - else - { - // all fixed bodies (inf mass) get mapped to a single solver id - if ( m_fixedBodyId < 0 ) - { - m_bodySolverArrayMutex.lock(); - // now that we have the lock, check again - if ( m_fixedBodyId < 0 ) - { - m_fixedBodyId = m_tmpSolverBodyPool.size(); - btSolverBody& fixedBody = m_tmpSolverBodyPool.expand(); - initSolverBody( &fixedBody, 0, timeStep ); - } - m_bodySolverArrayMutex.unlock(); - } - solverBodyId = m_fixedBodyId; - } - btAssert( solverBodyId >= 0 && solverBodyId < m_tmpSolverBodyPool.size() ); - return solverBodyId; -} - - -void btSequentialImpulseConstraintSolverMt::internalCollectContactManifoldCachedInfo(btContactManifoldCachedInfo* cachedInfoArray, btPersistentManifold** manifoldPtr, int numManifolds, const btContactSolverInfo& infoGlobal) -{ - BT_PROFILE("internalCollectContactManifoldCachedInfo"); - for (int i = 0; i < numManifolds; ++i) - { - btContactManifoldCachedInfo* cachedInfo = &cachedInfoArray[i]; - btPersistentManifold* manifold = manifoldPtr[i]; - btCollisionObject* colObj0 = (btCollisionObject*) manifold->getBody0(); - btCollisionObject* colObj1 = (btCollisionObject*) manifold->getBody1(); - - int solverBodyIdA = getOrInitSolverBodyThreadsafe( *colObj0, infoGlobal.m_timeStep ); - int solverBodyIdB = getOrInitSolverBodyThreadsafe( *colObj1, infoGlobal.m_timeStep ); - - cachedInfo->solverBodyIds[ 0 ] = solverBodyIdA; - cachedInfo->solverBodyIds[ 1 ] = solverBodyIdB; - cachedInfo->numTouchingContacts = 0; - - btSolverBody* solverBodyA = &m_tmpSolverBodyPool[ solverBodyIdA ]; - btSolverBody* solverBodyB = &m_tmpSolverBodyPool[ solverBodyIdB ]; - - // A contact manifold between 2 static object should not exist! - // check the collision flags of your objects if this assert fires. - // Incorrectly set collision object flags can degrade performance in various ways. - btAssert( !m_tmpSolverBodyPool[ solverBodyIdA ].m_invMass.isZero() || !m_tmpSolverBodyPool[ solverBodyIdB ].m_invMass.isZero() ); - - int iContact = 0; - for ( int j = 0; j < manifold->getNumContacts(); j++ ) - { - btManifoldPoint& cp = manifold->getContactPoint( j ); - - if ( cp.getDistance() <= manifold->getContactProcessingThreshold() ) - { - cachedInfo->contactPoints[ iContact ] = &cp; - cachedInfo->contactHasRollingFriction[ iContact ] = ( cp.m_combinedRollingFriction > 0.f ); - iContact++; - } - } - cachedInfo->numTouchingContacts = iContact; - } -} - - -struct CollectContactManifoldCachedInfoLoop : public btIParallelForBody -{ - btSequentialImpulseConstraintSolverMt* m_solver; - btSequentialImpulseConstraintSolverMt::btContactManifoldCachedInfo* m_cachedInfoArray; - btPersistentManifold** m_manifoldPtr; - const btContactSolverInfo* m_infoGlobal; - - CollectContactManifoldCachedInfoLoop( btSequentialImpulseConstraintSolverMt* solver, btSequentialImpulseConstraintSolverMt::btContactManifoldCachedInfo* cachedInfoArray, btPersistentManifold** manifoldPtr, const btContactSolverInfo& infoGlobal ) - { - m_solver = solver; - m_cachedInfoArray = cachedInfoArray; - m_manifoldPtr = manifoldPtr; - m_infoGlobal = &infoGlobal; - } - void forLoop( int iBegin, int iEnd ) const BT_OVERRIDE - { - m_solver->internalCollectContactManifoldCachedInfo( m_cachedInfoArray + iBegin, m_manifoldPtr + iBegin, iEnd - iBegin, *m_infoGlobal ); - } -}; - - -void btSequentialImpulseConstraintSolverMt::internalAllocContactConstraints(const btContactManifoldCachedInfo* cachedInfoArray, int numManifolds) -{ - BT_PROFILE("internalAllocContactConstraints"); - // possibly parallel part - for ( int iManifold = 0; iManifold < numManifolds; ++iManifold ) - { - const btContactManifoldCachedInfo& cachedInfo = cachedInfoArray[ iManifold ]; - int contactIndex = cachedInfo.contactIndex; - int frictionIndex = contactIndex * m_numFrictionDirections; - int rollingFrictionIndex = cachedInfo.rollingFrictionIndex; - for ( int i = 0; i < cachedInfo.numTouchingContacts; i++ ) - { - btSolverConstraint& contactConstraint = m_tmpSolverContactConstraintPool[contactIndex]; - contactConstraint.m_solverBodyIdA = cachedInfo.solverBodyIds[ 0 ]; - contactConstraint.m_solverBodyIdB = cachedInfo.solverBodyIds[ 1 ]; - contactConstraint.m_originalContactPoint = cachedInfo.contactPoints[ i ]; - - // allocate the friction constraints - contactConstraint.m_frictionIndex = frictionIndex; - for ( int iDir = 0; iDir < m_numFrictionDirections; ++iDir ) - { - btSolverConstraint& frictionConstraint = m_tmpSolverContactFrictionConstraintPool[frictionIndex]; - frictionConstraint.m_frictionIndex = contactIndex; - frictionIndex++; - } - - // allocate rolling friction constraints - if ( cachedInfo.contactHasRollingFriction[ i ] ) - { - m_rollingFrictionIndexTable[ contactIndex ] = rollingFrictionIndex; - // allocate 3 (although we may use only 2 sometimes) - for ( int i = 0; i < 3; i++ ) - { - m_tmpSolverContactRollingFrictionConstraintPool[ rollingFrictionIndex ].m_frictionIndex = contactIndex; - rollingFrictionIndex++; - } - } - else - { - // indicate there is no rolling friction for this contact point - m_rollingFrictionIndexTable[ contactIndex ] = -1; - } - contactIndex++; - } - } -} - - -struct AllocContactConstraintsLoop : public btIParallelForBody -{ - btSequentialImpulseConstraintSolverMt* m_solver; - const btSequentialImpulseConstraintSolverMt::btContactManifoldCachedInfo* m_cachedInfoArray; - - AllocContactConstraintsLoop( btSequentialImpulseConstraintSolverMt* solver, btSequentialImpulseConstraintSolverMt::btContactManifoldCachedInfo* cachedInfoArray ) - { - m_solver = solver; - m_cachedInfoArray = cachedInfoArray; - } - void forLoop( int iBegin, int iEnd ) const BT_OVERRIDE - { - m_solver->internalAllocContactConstraints( m_cachedInfoArray + iBegin, iEnd - iBegin ); - } -}; - - -void btSequentialImpulseConstraintSolverMt::allocAllContactConstraints(btPersistentManifold** manifoldPtr, int numManifolds, const btContactSolverInfo& infoGlobal) -{ - BT_PROFILE( "allocAllContactConstraints" ); - btAlignedObjectArray cachedInfoArray; // = m_manifoldCachedInfoArray; - cachedInfoArray.resizeNoInitialize( numManifolds ); - if (/* DISABLES CODE */ (false)) - { - // sequential - internalCollectContactManifoldCachedInfo(&cachedInfoArray[ 0 ], manifoldPtr, numManifolds, infoGlobal); - } - else - { - // may alter ordering of bodies which affects determinism - CollectContactManifoldCachedInfoLoop loop( this, &cachedInfoArray[ 0 ], manifoldPtr, infoGlobal ); - int grainSize = 200; - btParallelFor( 0, numManifolds, grainSize, loop ); - } - - { - // serial part - int numContacts = 0; - int numRollingFrictionConstraints = 0; - for ( int iManifold = 0; iManifold < numManifolds; ++iManifold ) - { - btContactManifoldCachedInfo& cachedInfo = cachedInfoArray[ iManifold ]; - cachedInfo.contactIndex = numContacts; - cachedInfo.rollingFrictionIndex = numRollingFrictionConstraints; - numContacts += cachedInfo.numTouchingContacts; - for (int i = 0; i < cachedInfo.numTouchingContacts; ++i) - { - if (cachedInfo.contactHasRollingFriction[i]) - { - numRollingFrictionConstraints += 3; - } - } - } - { - BT_PROFILE( "allocPools" ); - if ( m_tmpSolverContactConstraintPool.capacity() < numContacts ) - { - // if we need to reallocate, reserve some extra so we don't have to reallocate again next frame - int extraReserve = numContacts / 16; - m_tmpSolverContactConstraintPool.reserve( numContacts + extraReserve ); - m_rollingFrictionIndexTable.reserve( numContacts + extraReserve ); - m_tmpSolverContactFrictionConstraintPool.reserve( ( numContacts + extraReserve )*m_numFrictionDirections ); - m_tmpSolverContactRollingFrictionConstraintPool.reserve( numRollingFrictionConstraints + extraReserve ); - } - m_tmpSolverContactConstraintPool.resizeNoInitialize( numContacts ); - m_rollingFrictionIndexTable.resizeNoInitialize( numContacts ); - m_tmpSolverContactFrictionConstraintPool.resizeNoInitialize( numContacts*m_numFrictionDirections ); - m_tmpSolverContactRollingFrictionConstraintPool.resizeNoInitialize( numRollingFrictionConstraints ); - } - } - { - AllocContactConstraintsLoop loop(this, &cachedInfoArray[0]); - int grainSize = 200; - btParallelFor( 0, numManifolds, grainSize, loop ); - } -} - - -void btSequentialImpulseConstraintSolverMt::convertContacts(btPersistentManifold** manifoldPtr, int numManifolds, const btContactSolverInfo& infoGlobal) -{ - if (!m_useBatching) - { - btSequentialImpulseConstraintSolver::convertContacts(manifoldPtr, numManifolds, infoGlobal); - return; - } - BT_PROFILE( "convertContacts" ); - if (numManifolds > 0) - { - if ( m_fixedBodyId < 0 ) - { - m_fixedBodyId = m_tmpSolverBodyPool.size(); - btSolverBody& fixedBody = m_tmpSolverBodyPool.expand(); - initSolverBody( &fixedBody, 0, infoGlobal.m_timeStep ); - } - allocAllContactConstraints( manifoldPtr, numManifolds, infoGlobal ); - if ( m_useBatching ) - { - setupBatchedContactConstraints(); - } - setupAllContactConstraints( infoGlobal ); - } -} - - -void btSequentialImpulseConstraintSolverMt::internalInitMultipleJoints( btTypedConstraint** constraints, int iBegin, int iEnd ) -{ - BT_PROFILE("internalInitMultipleJoints"); - for ( int i = iBegin; i < iEnd; i++ ) - { - btTypedConstraint* constraint = constraints[i]; - btTypedConstraint::btConstraintInfo1& info1 = m_tmpConstraintSizesPool[i]; - if (constraint->isEnabled()) - { - constraint->buildJacobian(); - constraint->internalSetAppliedImpulse( 0.0f ); - btJointFeedback* fb = constraint->getJointFeedback(); - if ( fb ) - { - fb->m_appliedForceBodyA.setZero(); - fb->m_appliedTorqueBodyA.setZero(); - fb->m_appliedForceBodyB.setZero(); - fb->m_appliedTorqueBodyB.setZero(); - } - constraint->getInfo1( &info1 ); - } - else - { - info1.m_numConstraintRows = 0; - info1.nub = 0; - } - } -} - - -struct InitJointsLoop : public btIParallelForBody -{ - btSequentialImpulseConstraintSolverMt* m_solver; - btTypedConstraint** m_constraints; - - InitJointsLoop( btSequentialImpulseConstraintSolverMt* solver, btTypedConstraint** constraints ) - { - m_solver = solver; - m_constraints = constraints; - } - void forLoop( int iBegin, int iEnd ) const BT_OVERRIDE - { - m_solver->internalInitMultipleJoints( m_constraints, iBegin, iEnd ); - } -}; - - -void btSequentialImpulseConstraintSolverMt::internalConvertMultipleJoints( const btAlignedObjectArray& jointParamsArray, btTypedConstraint** constraints, int iBegin, int iEnd, const btContactSolverInfo& infoGlobal ) -{ - BT_PROFILE("internalConvertMultipleJoints"); - for ( int i = iBegin; i < iEnd; ++i ) - { - const JointParams& jointParams = jointParamsArray[ i ]; - int currentRow = jointParams.m_solverConstraint; - if ( currentRow != -1 ) - { - const btTypedConstraint::btConstraintInfo1& info1 = m_tmpConstraintSizesPool[ i ]; - btAssert( currentRow < m_tmpSolverNonContactConstraintPool.size() ); - btAssert( info1.m_numConstraintRows > 0 ); - - btSolverConstraint* currentConstraintRow = &m_tmpSolverNonContactConstraintPool[ currentRow ]; - btTypedConstraint* constraint = constraints[ i ]; - - convertJoint( currentConstraintRow, constraint, info1, jointParams.m_solverBodyA, jointParams.m_solverBodyB, infoGlobal ); - } - } -} - - -struct ConvertJointsLoop : public btIParallelForBody -{ - btSequentialImpulseConstraintSolverMt* m_solver; - const btAlignedObjectArray& m_jointParamsArray; - btTypedConstraint** m_srcConstraints; - const btContactSolverInfo& m_infoGlobal; - - ConvertJointsLoop( btSequentialImpulseConstraintSolverMt* solver, - const btAlignedObjectArray& jointParamsArray, - btTypedConstraint** srcConstraints, - const btContactSolverInfo& infoGlobal - ) : - m_jointParamsArray(jointParamsArray), - m_infoGlobal(infoGlobal) - { - m_solver = solver; - m_srcConstraints = srcConstraints; - } - void forLoop( int iBegin, int iEnd ) const BT_OVERRIDE - { - m_solver->internalConvertMultipleJoints( m_jointParamsArray, m_srcConstraints, iBegin, iEnd, m_infoGlobal ); - } -}; - - -void btSequentialImpulseConstraintSolverMt::convertJoints(btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal) -{ - if ( !m_useBatching ) - { - btSequentialImpulseConstraintSolver::convertJoints(constraints, numConstraints, infoGlobal); - return; - } - BT_PROFILE("convertJoints"); - bool parallelJointSetup = true; - m_tmpConstraintSizesPool.resizeNoInitialize(numConstraints); - if (parallelJointSetup) - { - InitJointsLoop loop(this, constraints); - int grainSize = 40; - btParallelFor(0, numConstraints, grainSize, loop); - } - else - { - internalInitMultipleJoints( constraints, 0, numConstraints ); - } - - int totalNumRows = 0; - btAlignedObjectArray jointParamsArray; - jointParamsArray.resizeNoInitialize(numConstraints); - - //calculate the total number of contraint rows - for (int i=0;igetRigidBodyA(), infoGlobal.m_timeStep ); - params.m_solverBodyB = getOrInitSolverBody( constraint->getRigidBodyB(), infoGlobal.m_timeStep ); - } - else - { - params.m_solverConstraint = -1; - } - totalNumRows += info1.m_numConstraintRows; - } - m_tmpSolverNonContactConstraintPool.resizeNoInitialize(totalNumRows); - - ///setup the btSolverConstraints - if ( parallelJointSetup ) - { - ConvertJointsLoop loop(this, jointParamsArray, constraints, infoGlobal); - int grainSize = 20; - btParallelFor(0, numConstraints, grainSize, loop); - } - else - { - internalConvertMultipleJoints( jointParamsArray, constraints, 0, numConstraints, infoGlobal ); - } - setupBatchedJointConstraints(); -} - - -void btSequentialImpulseConstraintSolverMt::internalConvertBodies(btCollisionObject** bodies, int iBegin, int iEnd, const btContactSolverInfo& infoGlobal) -{ - BT_PROFILE("internalConvertBodies"); - for (int i=iBegin; i < iEnd; i++) - { - btCollisionObject* obj = bodies[i]; - obj->setCompanionId(i); - btSolverBody& solverBody = m_tmpSolverBodyPool[i]; - initSolverBody(&solverBody, obj, infoGlobal.m_timeStep); - - btRigidBody* body = btRigidBody::upcast(obj); - if (body && body->getInvMass()) - { - btVector3 gyroForce (0,0,0); - if (body->getFlags()&BT_ENABLE_GYROSCOPIC_FORCE_EXPLICIT) - { - gyroForce = body->computeGyroscopicForceExplicit(infoGlobal.m_maxGyroscopicForce); - solverBody.m_externalTorqueImpulse -= gyroForce*body->getInvInertiaTensorWorld()*infoGlobal.m_timeStep; - } - if (body->getFlags()&BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_WORLD) - { - gyroForce = body->computeGyroscopicImpulseImplicit_World(infoGlobal.m_timeStep); - solverBody.m_externalTorqueImpulse += gyroForce; - } - if (body->getFlags()&BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_BODY) - { - gyroForce = body->computeGyroscopicImpulseImplicit_Body(infoGlobal.m_timeStep); - solverBody.m_externalTorqueImpulse += gyroForce; - } - } - } -} - - -struct ConvertBodiesLoop : public btIParallelForBody -{ - btSequentialImpulseConstraintSolverMt* m_solver; - btCollisionObject** m_bodies; - int m_numBodies; - const btContactSolverInfo& m_infoGlobal; - - ConvertBodiesLoop( btSequentialImpulseConstraintSolverMt* solver, - btCollisionObject** bodies, - int numBodies, - const btContactSolverInfo& infoGlobal - ) : - m_infoGlobal(infoGlobal) - { - m_solver = solver; - m_bodies = bodies; - m_numBodies = numBodies; - } - void forLoop( int iBegin, int iEnd ) const BT_OVERRIDE - { - m_solver->internalConvertBodies( m_bodies, iBegin, iEnd, m_infoGlobal ); - } -}; - - -void btSequentialImpulseConstraintSolverMt::convertBodies(btCollisionObject** bodies, int numBodies, const btContactSolverInfo& infoGlobal) -{ - BT_PROFILE("convertBodies"); - m_kinematicBodyUniqueIdToSolverBodyTable.resize( 0 ); - - m_tmpSolverBodyPool.resizeNoInitialize(numBodies+1); - - m_fixedBodyId = numBodies; - { - btSolverBody& fixedBody = m_tmpSolverBodyPool[ m_fixedBodyId ]; - initSolverBody( &fixedBody, NULL, infoGlobal.m_timeStep ); - } - - bool parallelBodySetup = true; - if (parallelBodySetup) - { - ConvertBodiesLoop loop(this, bodies, numBodies, infoGlobal); - int grainSize = 40; - btParallelFor(0, numBodies, grainSize, loop); - } - else - { - internalConvertBodies( bodies, 0, numBodies, infoGlobal ); - } -} - - -btScalar btSequentialImpulseConstraintSolverMt::solveGroupCacheFriendlySetup( - btCollisionObject** bodies, - int numBodies, - btPersistentManifold** manifoldPtr, - int numManifolds, - btTypedConstraint** constraints, - int numConstraints, - const btContactSolverInfo& infoGlobal, - btIDebugDraw* debugDrawer - ) -{ - m_numFrictionDirections = (infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS) ? 2 : 1; - m_useBatching = false; - if ( numManifolds >= s_minimumContactManifoldsForBatching && - (s_allowNestedParallelForLoops || !btThreadsAreRunning()) - ) - { - m_useBatching = true; - m_batchedContactConstraints.m_debugDrawer = debugDrawer; - m_batchedJointConstraints.m_debugDrawer = debugDrawer; - } - btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySetup( bodies, - numBodies, - manifoldPtr, - numManifolds, - constraints, - numConstraints, - infoGlobal, - debugDrawer - ); - return 0.0f; -} - - -btScalar btSequentialImpulseConstraintSolverMt::resolveMultipleContactSplitPenetrationImpulseConstraints( const btAlignedObjectArray& consIndices, int batchBegin, int batchEnd ) -{ - btScalar leastSquaresResidual = 0.f; - for ( int iiCons = batchBegin; iiCons < batchEnd; ++iiCons ) - { - int iCons = consIndices[ iiCons ]; - const btSolverConstraint& solveManifold = m_tmpSolverContactConstraintPool[ iCons ]; - btSolverBody& bodyA = m_tmpSolverBodyPool[ solveManifold.m_solverBodyIdA ]; - btSolverBody& bodyB = m_tmpSolverBodyPool[ solveManifold.m_solverBodyIdB ]; - btScalar residual = resolveSplitPenetrationImpulse( bodyA, bodyB, solveManifold ); - leastSquaresResidual += residual*residual; - } - return leastSquaresResidual; -} - - -struct ContactSplitPenetrationImpulseSolverLoop : public btIParallelSumBody -{ - btSequentialImpulseConstraintSolverMt* m_solver; - const btBatchedConstraints* m_bc; - - ContactSplitPenetrationImpulseSolverLoop( btSequentialImpulseConstraintSolverMt* solver, const btBatchedConstraints* bc ) - { - m_solver = solver; - m_bc = bc; - } - btScalar sumLoop( int iBegin, int iEnd ) const BT_OVERRIDE - { - BT_PROFILE( "ContactSplitPenetrationImpulseSolverLoop" ); - btScalar sum = 0; - for ( int iBatch = iBegin; iBatch < iEnd; ++iBatch ) - { - const btBatchedConstraints::Range& batch = m_bc->m_batches[ iBatch ]; - sum += m_solver->resolveMultipleContactSplitPenetrationImpulseConstraints( m_bc->m_constraintIndices, batch.begin, batch.end ); - } - return sum; - } -}; - - -void btSequentialImpulseConstraintSolverMt::solveGroupCacheFriendlySplitImpulseIterations(btCollisionObject** bodies,int numBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer) -{ - BT_PROFILE("solveGroupCacheFriendlySplitImpulseIterations"); - if (infoGlobal.m_splitImpulse) - { - for ( int iteration = 0; iteration < infoGlobal.m_numIterations; iteration++ ) - { - btScalar leastSquaresResidual = 0.f; - if (m_useBatching) - { - const btBatchedConstraints& batchedCons = m_batchedContactConstraints; - ContactSplitPenetrationImpulseSolverLoop loop( this, &batchedCons ); - btScalar leastSquaresResidual = 0.f; - for ( int iiPhase = 0; iiPhase < batchedCons.m_phases.size(); ++iiPhase ) - { - int iPhase = batchedCons.m_phaseOrder[ iiPhase ]; - const btBatchedConstraints::Range& phase = batchedCons.m_phases[ iPhase ]; - int grainSize = batchedCons.m_phaseGrainSize[iPhase]; - leastSquaresResidual += btParallelSum( phase.begin, phase.end, grainSize, loop ); - } - } - else - { - // non-batched - leastSquaresResidual = resolveMultipleContactSplitPenetrationImpulseConstraints(m_orderTmpConstraintPool, 0, m_tmpSolverContactConstraintPool.size()); - } - if ( leastSquaresResidual <= infoGlobal.m_leastSquaresResidualThreshold || iteration >= ( infoGlobal.m_numIterations - 1 ) ) - { -#ifdef VERBOSE_RESIDUAL_PRINTF - printf( "residual = %f at iteration #%d\n", leastSquaresResidual, iteration ); -#endif - break; - } - } - } -} - - -btScalar btSequentialImpulseConstraintSolverMt::solveSingleIteration(int iteration, btCollisionObject** bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer) -{ - if ( !m_useBatching ) - { - return btSequentialImpulseConstraintSolver::solveSingleIteration( iteration, bodies, numBodies, manifoldPtr, numManifolds, constraints, numConstraints, infoGlobal, debugDrawer ); - } - BT_PROFILE( "solveSingleIterationMt" ); - btScalar leastSquaresResidual = 0.f; - - if (infoGlobal.m_solverMode & SOLVER_RANDMIZE_ORDER) - { - if (1) // uncomment this for a bit less random ((iteration & 7) == 0) - { - randomizeConstraintOrdering(iteration, infoGlobal.m_numIterations); - } - } - - { - ///solve all joint constraints - leastSquaresResidual += resolveAllJointConstraints(iteration); - - if (iteration< infoGlobal.m_numIterations) - { - // this loop is only used for cone-twist constraints, - // it would be nice to skip this loop if none of the constraints need it - if ( m_useObsoleteJointConstraints ) - { - for ( int j = 0; jisEnabled() ) - { - int bodyAid = getOrInitSolverBody( constraints[ j ]->getRigidBodyA(), infoGlobal.m_timeStep ); - int bodyBid = getOrInitSolverBody( constraints[ j ]->getRigidBodyB(), infoGlobal.m_timeStep ); - btSolverBody& bodyA = m_tmpSolverBodyPool[ bodyAid ]; - btSolverBody& bodyB = m_tmpSolverBodyPool[ bodyBid ]; - constraints[ j ]->solveConstraintObsolete( bodyA, bodyB, infoGlobal.m_timeStep ); - } - } - } - - if (infoGlobal.m_solverMode & SOLVER_INTERLEAVE_CONTACT_AND_FRICTION_CONSTRAINTS) - { - // solve all contact, contact-friction, and rolling friction constraints interleaved - leastSquaresResidual += resolveAllContactConstraintsInterleaved(); - } - else//SOLVER_INTERLEAVE_CONTACT_AND_FRICTION_CONSTRAINTS - { - // don't interleave them - // solve all contact constraints - leastSquaresResidual += resolveAllContactConstraints(); - - // solve all contact friction constraints - leastSquaresResidual += resolveAllContactFrictionConstraints(); - - // solve all rolling friction constraints - leastSquaresResidual += resolveAllRollingFrictionConstraints(); - } - } - } - return leastSquaresResidual; -} - - -btScalar btSequentialImpulseConstraintSolverMt::resolveMultipleJointConstraints( const btAlignedObjectArray& consIndices, int batchBegin, int batchEnd, int iteration ) -{ - btScalar leastSquaresResidual = 0.f; - for ( int iiCons = batchBegin; iiCons < batchEnd; ++iiCons ) - { - int iCons = consIndices[ iiCons ]; - const btSolverConstraint& constraint = m_tmpSolverNonContactConstraintPool[ iCons ]; - if ( iteration < constraint.m_overrideNumSolverIterations ) - { - btSolverBody& bodyA = m_tmpSolverBodyPool[ constraint.m_solverBodyIdA ]; - btSolverBody& bodyB = m_tmpSolverBodyPool[ constraint.m_solverBodyIdB ]; - btScalar residual = resolveSingleConstraintRowGeneric( bodyA, bodyB, constraint ); - leastSquaresResidual += residual*residual; - } - } - return leastSquaresResidual; -} - - -btScalar btSequentialImpulseConstraintSolverMt::resolveMultipleContactConstraints( const btAlignedObjectArray& consIndices, int batchBegin, int batchEnd ) -{ - btScalar leastSquaresResidual = 0.f; - for ( int iiCons = batchBegin; iiCons < batchEnd; ++iiCons ) - { - int iCons = consIndices[ iiCons ]; - const btSolverConstraint& solveManifold = m_tmpSolverContactConstraintPool[ iCons ]; - btSolverBody& bodyA = m_tmpSolverBodyPool[ solveManifold.m_solverBodyIdA ]; - btSolverBody& bodyB = m_tmpSolverBodyPool[ solveManifold.m_solverBodyIdB ]; - btScalar residual = resolveSingleConstraintRowLowerLimit( bodyA, bodyB, solveManifold ); - leastSquaresResidual += residual*residual; - } - return leastSquaresResidual; -} - - -btScalar btSequentialImpulseConstraintSolverMt::resolveMultipleContactFrictionConstraints( const btAlignedObjectArray& consIndices, int batchBegin, int batchEnd ) -{ - btScalar leastSquaresResidual = 0.f; - for ( int iiCons = batchBegin; iiCons < batchEnd; ++iiCons ) - { - int iContact = consIndices[ iiCons ]; - btScalar totalImpulse = m_tmpSolverContactConstraintPool[ iContact ].m_appliedImpulse; - - // apply sliding friction - if ( totalImpulse > 0.0f ) - { - int iBegin = iContact * m_numFrictionDirections; - int iEnd = iBegin + m_numFrictionDirections; - for ( int iFriction = iBegin; iFriction < iEnd; ++iFriction ) - { - btSolverConstraint& solveManifold = m_tmpSolverContactFrictionConstraintPool[ iFriction++ ]; - btAssert( solveManifold.m_frictionIndex == iContact ); - - solveManifold.m_lowerLimit = -( solveManifold.m_friction*totalImpulse ); - solveManifold.m_upperLimit = solveManifold.m_friction*totalImpulse; - - btSolverBody& bodyA = m_tmpSolverBodyPool[ solveManifold.m_solverBodyIdA ]; - btSolverBody& bodyB = m_tmpSolverBodyPool[ solveManifold.m_solverBodyIdB ]; - btScalar residual = resolveSingleConstraintRowGeneric( bodyA, bodyB, solveManifold ); - leastSquaresResidual += residual*residual; - } - } - } - return leastSquaresResidual; -} - - -btScalar btSequentialImpulseConstraintSolverMt::resolveMultipleContactRollingFrictionConstraints( const btAlignedObjectArray& consIndices, int batchBegin, int batchEnd ) -{ - btScalar leastSquaresResidual = 0.f; - for ( int iiCons = batchBegin; iiCons < batchEnd; ++iiCons ) - { - int iContact = consIndices[ iiCons ]; - int iFirstRollingFriction = m_rollingFrictionIndexTable[ iContact ]; - if ( iFirstRollingFriction >= 0 ) - { - btScalar totalImpulse = m_tmpSolverContactConstraintPool[ iContact ].m_appliedImpulse; - // apply rolling friction - if ( totalImpulse > 0.0f ) - { - int iBegin = iFirstRollingFriction; - int iEnd = iBegin + 3; - for ( int iRollingFric = iBegin; iRollingFric < iEnd; ++iRollingFric ) - { - btSolverConstraint& rollingFrictionConstraint = m_tmpSolverContactRollingFrictionConstraintPool[ iRollingFric ]; - if ( rollingFrictionConstraint.m_frictionIndex != iContact ) - { - break; - } - btScalar rollingFrictionMagnitude = rollingFrictionConstraint.m_friction*totalImpulse; - if ( rollingFrictionMagnitude > rollingFrictionConstraint.m_friction ) - { - rollingFrictionMagnitude = rollingFrictionConstraint.m_friction; - } - - rollingFrictionConstraint.m_lowerLimit = -rollingFrictionMagnitude; - rollingFrictionConstraint.m_upperLimit = rollingFrictionMagnitude; - - btScalar residual = resolveSingleConstraintRowGeneric( m_tmpSolverBodyPool[ rollingFrictionConstraint.m_solverBodyIdA ], m_tmpSolverBodyPool[ rollingFrictionConstraint.m_solverBodyIdB ], rollingFrictionConstraint ); - leastSquaresResidual += residual*residual; - } - } - } - } - return leastSquaresResidual; -} - - -btScalar btSequentialImpulseConstraintSolverMt::resolveMultipleContactConstraintsInterleaved( const btAlignedObjectArray& contactIndices, - int batchBegin, - int batchEnd - ) -{ - btScalar leastSquaresResidual = 0.f; - int numPoolConstraints = m_tmpSolverContactConstraintPool.size(); - - for ( int iiCons = batchBegin; iiCons < batchEnd; iiCons++ ) - { - btScalar totalImpulse = 0; - int iContact = contactIndices[ iiCons ]; - // apply penetration constraint - { - const btSolverConstraint& solveManifold = m_tmpSolverContactConstraintPool[ iContact ]; - btScalar residual = resolveSingleConstraintRowLowerLimit( m_tmpSolverBodyPool[ solveManifold.m_solverBodyIdA ], m_tmpSolverBodyPool[ solveManifold.m_solverBodyIdB ], solveManifold ); - leastSquaresResidual += residual*residual; - totalImpulse = solveManifold.m_appliedImpulse; - } - - // apply sliding friction - if ( totalImpulse > 0.0f ) - { - int iBegin = iContact * m_numFrictionDirections; - int iEnd = iBegin + m_numFrictionDirections; - for ( int iFriction = iBegin; iFriction < iEnd; ++iFriction ) - { - btSolverConstraint& solveManifold = m_tmpSolverContactFrictionConstraintPool[ iFriction ]; - btAssert( solveManifold.m_frictionIndex == iContact ); - - solveManifold.m_lowerLimit = -( solveManifold.m_friction*totalImpulse ); - solveManifold.m_upperLimit = solveManifold.m_friction*totalImpulse; - - btSolverBody& bodyA = m_tmpSolverBodyPool[ solveManifold.m_solverBodyIdA ]; - btSolverBody& bodyB = m_tmpSolverBodyPool[ solveManifold.m_solverBodyIdB ]; - btScalar residual = resolveSingleConstraintRowGeneric( bodyA, bodyB, solveManifold ); - leastSquaresResidual += residual*residual; - } - } - - // apply rolling friction - int iFirstRollingFriction = m_rollingFrictionIndexTable[ iContact ]; - if ( totalImpulse > 0.0f && iFirstRollingFriction >= 0) - { - int iBegin = iFirstRollingFriction; - int iEnd = iBegin + 3; - for ( int iRollingFric = iBegin; iRollingFric < iEnd; ++iRollingFric ) - { - btSolverConstraint& rollingFrictionConstraint = m_tmpSolverContactRollingFrictionConstraintPool[ iRollingFric ]; - if ( rollingFrictionConstraint.m_frictionIndex != iContact ) - { - break; - } - btScalar rollingFrictionMagnitude = rollingFrictionConstraint.m_friction*totalImpulse; - if ( rollingFrictionMagnitude > rollingFrictionConstraint.m_friction ) - { - rollingFrictionMagnitude = rollingFrictionConstraint.m_friction; - } - - rollingFrictionConstraint.m_lowerLimit = -rollingFrictionMagnitude; - rollingFrictionConstraint.m_upperLimit = rollingFrictionMagnitude; - - btScalar residual = resolveSingleConstraintRowGeneric( m_tmpSolverBodyPool[ rollingFrictionConstraint.m_solverBodyIdA ], m_tmpSolverBodyPool[ rollingFrictionConstraint.m_solverBodyIdB ], rollingFrictionConstraint ); - leastSquaresResidual += residual*residual; - } - } - } - return leastSquaresResidual; -} - - -void btSequentialImpulseConstraintSolverMt::randomizeBatchedConstraintOrdering( btBatchedConstraints* batchedConstraints ) -{ - btBatchedConstraints& bc = *batchedConstraints; - // randomize ordering of phases - for ( int ii = 1; ii < bc.m_phaseOrder.size(); ++ii ) - { - int iSwap = btRandInt2( ii + 1 ); - bc.m_phaseOrder.swap( ii, iSwap ); - } - - // for each batch, - for ( int iBatch = 0; iBatch < bc.m_batches.size(); ++iBatch ) - { - // randomize ordering of constraints within the batch - const btBatchedConstraints::Range& batch = bc.m_batches[ iBatch ]; - for ( int iiCons = batch.begin; iiCons < batch.end; ++iiCons ) - { - int iSwap = batch.begin + btRandInt2( iiCons - batch.begin + 1 ); - btAssert(iSwap >= batch.begin && iSwap < batch.end); - bc.m_constraintIndices.swap( iiCons, iSwap ); - } - } -} - - -void btSequentialImpulseConstraintSolverMt::randomizeConstraintOrdering(int iteration, int numIterations) -{ - // randomize ordering of joint constraints - randomizeBatchedConstraintOrdering( &m_batchedJointConstraints ); - - //contact/friction constraints are not solved more than numIterations - if ( iteration < numIterations ) - { - randomizeBatchedConstraintOrdering( &m_batchedContactConstraints ); - } -} - - -struct JointSolverLoop : public btIParallelSumBody -{ - btSequentialImpulseConstraintSolverMt* m_solver; - const btBatchedConstraints* m_bc; - int m_iteration; - - JointSolverLoop( btSequentialImpulseConstraintSolverMt* solver, const btBatchedConstraints* bc, int iteration ) - { - m_solver = solver; - m_bc = bc; - m_iteration = iteration; - } - btScalar sumLoop( int iBegin, int iEnd ) const BT_OVERRIDE - { - BT_PROFILE( "JointSolverLoop" ); - btScalar sum = 0; - for ( int iBatch = iBegin; iBatch < iEnd; ++iBatch ) - { - const btBatchedConstraints::Range& batch = m_bc->m_batches[ iBatch ]; - sum += m_solver->resolveMultipleJointConstraints( m_bc->m_constraintIndices, batch.begin, batch.end, m_iteration ); - } - return sum; - } -}; - - -btScalar btSequentialImpulseConstraintSolverMt::resolveAllJointConstraints(int iteration) -{ - BT_PROFILE( "resolveAllJointConstraints" ); - const btBatchedConstraints& batchedCons = m_batchedJointConstraints; - JointSolverLoop loop( this, &batchedCons, iteration ); - btScalar leastSquaresResidual = 0.f; - for ( int iiPhase = 0; iiPhase < batchedCons.m_phases.size(); ++iiPhase ) - { - int iPhase = batchedCons.m_phaseOrder[ iiPhase ]; - const btBatchedConstraints::Range& phase = batchedCons.m_phases[ iPhase ]; - int grainSize = 1; - leastSquaresResidual += btParallelSum( phase.begin, phase.end, grainSize, loop ); - } - return leastSquaresResidual; -} - - -struct ContactSolverLoop : public btIParallelSumBody -{ - btSequentialImpulseConstraintSolverMt* m_solver; - const btBatchedConstraints* m_bc; - - ContactSolverLoop( btSequentialImpulseConstraintSolverMt* solver, const btBatchedConstraints* bc ) - { - m_solver = solver; - m_bc = bc; - } - btScalar sumLoop( int iBegin, int iEnd ) const BT_OVERRIDE - { - BT_PROFILE( "ContactSolverLoop" ); - btScalar sum = 0; - for ( int iBatch = iBegin; iBatch < iEnd; ++iBatch ) - { - const btBatchedConstraints::Range& batch = m_bc->m_batches[ iBatch ]; - sum += m_solver->resolveMultipleContactConstraints( m_bc->m_constraintIndices, batch.begin, batch.end ); - } - return sum; - } -}; - - -btScalar btSequentialImpulseConstraintSolverMt::resolveAllContactConstraints() -{ - BT_PROFILE( "resolveAllContactConstraints" ); - const btBatchedConstraints& batchedCons = m_batchedContactConstraints; - ContactSolverLoop loop( this, &batchedCons ); - btScalar leastSquaresResidual = 0.f; - for ( int iiPhase = 0; iiPhase < batchedCons.m_phases.size(); ++iiPhase ) - { - int iPhase = batchedCons.m_phaseOrder[ iiPhase ]; - const btBatchedConstraints::Range& phase = batchedCons.m_phases[ iPhase ]; - int grainSize = batchedCons.m_phaseGrainSize[iPhase]; - leastSquaresResidual += btParallelSum( phase.begin, phase.end, grainSize, loop ); - } - return leastSquaresResidual; -} - - -struct ContactFrictionSolverLoop : public btIParallelSumBody -{ - btSequentialImpulseConstraintSolverMt* m_solver; - const btBatchedConstraints* m_bc; - - ContactFrictionSolverLoop( btSequentialImpulseConstraintSolverMt* solver, const btBatchedConstraints* bc ) - { - m_solver = solver; - m_bc = bc; - } - btScalar sumLoop( int iBegin, int iEnd ) const BT_OVERRIDE - { - BT_PROFILE( "ContactFrictionSolverLoop" ); - btScalar sum = 0; - for ( int iBatch = iBegin; iBatch < iEnd; ++iBatch ) - { - const btBatchedConstraints::Range& batch = m_bc->m_batches[ iBatch ]; - sum += m_solver->resolveMultipleContactFrictionConstraints( m_bc->m_constraintIndices, batch.begin, batch.end ); - } - return sum; - } -}; - - -btScalar btSequentialImpulseConstraintSolverMt::resolveAllContactFrictionConstraints() -{ - BT_PROFILE( "resolveAllContactFrictionConstraints" ); - const btBatchedConstraints& batchedCons = m_batchedContactConstraints; - ContactFrictionSolverLoop loop( this, &batchedCons ); - btScalar leastSquaresResidual = 0.f; - for ( int iiPhase = 0; iiPhase < batchedCons.m_phases.size(); ++iiPhase ) - { - int iPhase = batchedCons.m_phaseOrder[ iiPhase ]; - const btBatchedConstraints::Range& phase = batchedCons.m_phases[ iPhase ]; - int grainSize = batchedCons.m_phaseGrainSize[iPhase]; - leastSquaresResidual += btParallelSum( phase.begin, phase.end, grainSize, loop ); - } - return leastSquaresResidual; -} - - -struct InterleavedContactSolverLoop : public btIParallelSumBody -{ - btSequentialImpulseConstraintSolverMt* m_solver; - const btBatchedConstraints* m_bc; - - InterleavedContactSolverLoop( btSequentialImpulseConstraintSolverMt* solver, const btBatchedConstraints* bc ) - { - m_solver = solver; - m_bc = bc; - } - btScalar sumLoop( int iBegin, int iEnd ) const BT_OVERRIDE - { - BT_PROFILE( "InterleavedContactSolverLoop" ); - btScalar sum = 0; - for ( int iBatch = iBegin; iBatch < iEnd; ++iBatch ) - { - const btBatchedConstraints::Range& batch = m_bc->m_batches[ iBatch ]; - sum += m_solver->resolveMultipleContactConstraintsInterleaved( m_bc->m_constraintIndices, batch.begin, batch.end ); - } - return sum; - } -}; - - -btScalar btSequentialImpulseConstraintSolverMt::resolveAllContactConstraintsInterleaved() -{ - BT_PROFILE( "resolveAllContactConstraintsInterleaved" ); - const btBatchedConstraints& batchedCons = m_batchedContactConstraints; - InterleavedContactSolverLoop loop( this, &batchedCons ); - btScalar leastSquaresResidual = 0.f; - for ( int iiPhase = 0; iiPhase < batchedCons.m_phases.size(); ++iiPhase ) - { - int iPhase = batchedCons.m_phaseOrder[ iiPhase ]; - const btBatchedConstraints::Range& phase = batchedCons.m_phases[ iPhase ]; - int grainSize = 1; - leastSquaresResidual += btParallelSum( phase.begin, phase.end, grainSize, loop ); - } - return leastSquaresResidual; -} - - -struct ContactRollingFrictionSolverLoop : public btIParallelSumBody -{ - btSequentialImpulseConstraintSolverMt* m_solver; - const btBatchedConstraints* m_bc; - - ContactRollingFrictionSolverLoop( btSequentialImpulseConstraintSolverMt* solver, const btBatchedConstraints* bc ) - { - m_solver = solver; - m_bc = bc; - } - btScalar sumLoop( int iBegin, int iEnd ) const BT_OVERRIDE - { - BT_PROFILE( "ContactFrictionSolverLoop" ); - btScalar sum = 0; - for ( int iBatch = iBegin; iBatch < iEnd; ++iBatch ) - { - const btBatchedConstraints::Range& batch = m_bc->m_batches[ iBatch ]; - sum += m_solver->resolveMultipleContactRollingFrictionConstraints( m_bc->m_constraintIndices, batch.begin, batch.end ); - } - return sum; - } -}; - - -btScalar btSequentialImpulseConstraintSolverMt::resolveAllRollingFrictionConstraints() -{ - BT_PROFILE( "resolveAllRollingFrictionConstraints" ); - btScalar leastSquaresResidual = 0.f; - // - // We do not generate batches for rolling friction constraints. We assume that - // one of two cases is true: - // - // 1. either most bodies in the simulation have rolling friction, in which case we can use the - // batches for contacts and use a lookup table to translate contact indices to rolling friction - // (ignoring any contact indices that don't map to a rolling friction constraint). As long as - // most contacts have a corresponding rolling friction constraint, this should parallelize well. - // - // -OR- - // - // 2. few bodies in the simulation have rolling friction, so it is not worth trying to use the - // batches from contacts as most of the contacts won't have corresponding rolling friction - // constraints and most threads would end up doing very little work. Most of the time would - // go to threading overhead, so we don't bother with threading. - // - int numRollingFrictionPoolConstraints = m_tmpSolverContactRollingFrictionConstraintPool.size(); - if (numRollingFrictionPoolConstraints >= m_tmpSolverContactConstraintPool.size()) - { - // use batching if there are many rolling friction constraints - const btBatchedConstraints& batchedCons = m_batchedContactConstraints; - ContactRollingFrictionSolverLoop loop( this, &batchedCons ); - btScalar leastSquaresResidual = 0.f; - for ( int iiPhase = 0; iiPhase < batchedCons.m_phases.size(); ++iiPhase ) - { - int iPhase = batchedCons.m_phaseOrder[ iiPhase ]; - const btBatchedConstraints::Range& phase = batchedCons.m_phases[ iPhase ]; - int grainSize = 1; - leastSquaresResidual += btParallelSum( phase.begin, phase.end, grainSize, loop ); - } - } - else - { - // no batching, also ignores SOLVER_RANDMIZE_ORDER - for ( int j = 0; j < numRollingFrictionPoolConstraints; j++ ) - { - btSolverConstraint& rollingFrictionConstraint = m_tmpSolverContactRollingFrictionConstraintPool[ j ]; - if ( rollingFrictionConstraint.m_frictionIndex >= 0 ) - { - btScalar totalImpulse = m_tmpSolverContactConstraintPool[ rollingFrictionConstraint.m_frictionIndex ].m_appliedImpulse; - if ( totalImpulse > 0.0f ) - { - btScalar rollingFrictionMagnitude = rollingFrictionConstraint.m_friction*totalImpulse; - if ( rollingFrictionMagnitude > rollingFrictionConstraint.m_friction ) - rollingFrictionMagnitude = rollingFrictionConstraint.m_friction; - - rollingFrictionConstraint.m_lowerLimit = -rollingFrictionMagnitude; - rollingFrictionConstraint.m_upperLimit = rollingFrictionMagnitude; - - btScalar residual = resolveSingleConstraintRowGeneric( m_tmpSolverBodyPool[ rollingFrictionConstraint.m_solverBodyIdA ], m_tmpSolverBodyPool[ rollingFrictionConstraint.m_solverBodyIdB ], rollingFrictionConstraint ); - leastSquaresResidual += residual*residual; - } - } - } - } - return leastSquaresResidual; -} - - -void btSequentialImpulseConstraintSolverMt::internalWriteBackContacts( int iBegin, int iEnd, const btContactSolverInfo& infoGlobal ) -{ - BT_PROFILE("internalWriteBackContacts"); - writeBackContacts(iBegin, iEnd, infoGlobal); - //for ( int iContact = iBegin; iContact < iEnd; ++iContact) - //{ - // const btSolverConstraint& contactConstraint = m_tmpSolverContactConstraintPool[ iContact ]; - // btManifoldPoint* pt = (btManifoldPoint*) contactConstraint.m_originalContactPoint; - // btAssert( pt ); - // pt->m_appliedImpulse = contactConstraint.m_appliedImpulse; - // pt->m_appliedImpulseLateral1 = m_tmpSolverContactFrictionConstraintPool[ contactConstraint.m_frictionIndex ].m_appliedImpulse; - // if ( m_numFrictionDirections == 2 ) - // { - // pt->m_appliedImpulseLateral2 = m_tmpSolverContactFrictionConstraintPool[ contactConstraint.m_frictionIndex + 1 ].m_appliedImpulse; - // } - //} -} - - -void btSequentialImpulseConstraintSolverMt::internalWriteBackJoints( int iBegin, int iEnd, const btContactSolverInfo& infoGlobal ) -{ - BT_PROFILE("internalWriteBackJoints"); - writeBackJoints(iBegin, iEnd, infoGlobal); -} - - -void btSequentialImpulseConstraintSolverMt::internalWriteBackBodies( int iBegin, int iEnd, const btContactSolverInfo& infoGlobal ) -{ - BT_PROFILE("internalWriteBackBodies"); - writeBackBodies( iBegin, iEnd, infoGlobal ); -} - - -struct WriteContactPointsLoop : public btIParallelForBody -{ - btSequentialImpulseConstraintSolverMt* m_solver; - const btContactSolverInfo* m_infoGlobal; - - WriteContactPointsLoop( btSequentialImpulseConstraintSolverMt* solver, const btContactSolverInfo& infoGlobal ) - { - m_solver = solver; - m_infoGlobal = &infoGlobal; - } - void forLoop( int iBegin, int iEnd ) const BT_OVERRIDE - { - m_solver->internalWriteBackContacts( iBegin, iEnd, *m_infoGlobal ); - } -}; - - -struct WriteJointsLoop : public btIParallelForBody -{ - btSequentialImpulseConstraintSolverMt* m_solver; - const btContactSolverInfo* m_infoGlobal; - - WriteJointsLoop( btSequentialImpulseConstraintSolverMt* solver, const btContactSolverInfo& infoGlobal ) - { - m_solver = solver; - m_infoGlobal = &infoGlobal; - } - void forLoop( int iBegin, int iEnd ) const BT_OVERRIDE - { - m_solver->internalWriteBackJoints( iBegin, iEnd, *m_infoGlobal ); - } -}; - - -struct WriteBodiesLoop : public btIParallelForBody -{ - btSequentialImpulseConstraintSolverMt* m_solver; - const btContactSolverInfo* m_infoGlobal; - - WriteBodiesLoop( btSequentialImpulseConstraintSolverMt* solver, const btContactSolverInfo& infoGlobal ) - { - m_solver = solver; - m_infoGlobal = &infoGlobal; - } - void forLoop( int iBegin, int iEnd ) const BT_OVERRIDE - { - m_solver->internalWriteBackBodies( iBegin, iEnd, *m_infoGlobal ); - } -}; - - -btScalar btSequentialImpulseConstraintSolverMt::solveGroupCacheFriendlyFinish(btCollisionObject** bodies, int numBodies, const btContactSolverInfo& infoGlobal) -{ - BT_PROFILE("solveGroupCacheFriendlyFinish"); - - if (infoGlobal.m_solverMode & SOLVER_USE_WARMSTARTING) - { - WriteContactPointsLoop loop( this, infoGlobal ); - int grainSize = 500; - btParallelFor( 0, m_tmpSolverContactConstraintPool.size(), grainSize, loop ); - } - - { - WriteJointsLoop loop( this, infoGlobal ); - int grainSize = 400; - btParallelFor( 0, m_tmpSolverNonContactConstraintPool.size(), grainSize, loop ); - } - { - WriteBodiesLoop loop( this, infoGlobal ); - int grainSize = 100; - btParallelFor( 0, m_tmpSolverBodyPool.size(), grainSize, loop ); - } - - m_tmpSolverContactConstraintPool.resizeNoInitialize(0); - m_tmpSolverNonContactConstraintPool.resizeNoInitialize(0); - m_tmpSolverContactFrictionConstraintPool.resizeNoInitialize(0); - m_tmpSolverContactRollingFrictionConstraintPool.resizeNoInitialize(0); - - m_tmpSolverBodyPool.resizeNoInitialize(0); - return 0.f; -} - diff --git a/extern/bullet/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.h b/extern/bullet/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.h deleted file mode 100644 index 55d53474c473..000000000000 --- a/extern/bullet/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.h +++ /dev/null @@ -1,154 +0,0 @@ -/* -Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#ifndef BT_SEQUENTIAL_IMPULSE_CONSTRAINT_SOLVER_MT_H -#define BT_SEQUENTIAL_IMPULSE_CONSTRAINT_SOLVER_MT_H - -#include "btSequentialImpulseConstraintSolver.h" -#include "btBatchedConstraints.h" -#include "LinearMath/btThreads.h" - -/// -/// btSequentialImpulseConstraintSolverMt -/// -/// A multithreaded variant of the sequential impulse constraint solver. The constraints to be solved are grouped into -/// batches and phases where each batch of constraints within a given phase can be solved in parallel with the rest. -/// Ideally we want as few phases as possible, and each phase should have many batches, and all of the batches should -/// have about the same number of constraints. -/// This method works best on a large island of many constraints. -/// -/// Supports all of the features of the normal sequential impulse solver such as: -/// - split penetration impulse -/// - rolling friction -/// - interleaving constraints -/// - warmstarting -/// - 2 friction directions -/// - randomized constraint ordering -/// - early termination when leastSquaresResidualThreshold is satisfied -/// -/// When the SOLVER_INTERLEAVE_CONTACT_AND_FRICTION_CONSTRAINTS flag is enabled, unlike the normal SequentialImpulse solver, -/// the rolling friction is interleaved as well. -/// Interleaving the contact penetration constraints with friction reduces the number of parallel loops that need to be done, -/// which reduces threading overhead so it can be a performance win, however, it does seem to produce a less stable simulation, -/// at least on stacks of blocks. -/// -/// When the SOLVER_RANDMIZE_ORDER flag is enabled, the ordering of phases, and the ordering of constraints within each batch -/// is randomized, however it does not swap constraints between batches. -/// This is to avoid regenerating the batches for each solver iteration which would be quite costly in performance. -/// -/// Note that a non-zero leastSquaresResidualThreshold could possibly affect the determinism of the simulation -/// if the task scheduler's parallelSum operation is non-deterministic. The parallelSum operation can be non-deterministic -/// because floating point addition is not associative due to rounding errors. -/// The task scheduler can and should ensure that the result of any parallelSum operation is deterministic. -/// -ATTRIBUTE_ALIGNED16(class) btSequentialImpulseConstraintSolverMt : public btSequentialImpulseConstraintSolver -{ -public: - virtual void solveGroupCacheFriendlySplitImpulseIterations(btCollisionObject** bodies,int numBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer) BT_OVERRIDE; - virtual btScalar solveSingleIteration(int iteration, btCollisionObject** bodies ,int numBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer) BT_OVERRIDE; - virtual btScalar solveGroupCacheFriendlySetup(btCollisionObject** bodies,int numBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer) BT_OVERRIDE; - virtual btScalar solveGroupCacheFriendlyFinish(btCollisionObject** bodies, int numBodies, const btContactSolverInfo& infoGlobal) BT_OVERRIDE; - - // temp struct used to collect info from persistent manifolds into a cache-friendly struct using multiple threads - struct btContactManifoldCachedInfo - { - static const int MAX_NUM_CONTACT_POINTS = 4; - - int numTouchingContacts; - int solverBodyIds[ 2 ]; - int contactIndex; - int rollingFrictionIndex; - bool contactHasRollingFriction[ MAX_NUM_CONTACT_POINTS ]; - btManifoldPoint* contactPoints[ MAX_NUM_CONTACT_POINTS ]; - }; - // temp struct used for setting up joint constraints in parallel - struct JointParams - { - int m_solverConstraint; - int m_solverBodyA; - int m_solverBodyB; - }; - void internalInitMultipleJoints(btTypedConstraint** constraints, int iBegin, int iEnd); - void internalConvertMultipleJoints( const btAlignedObjectArray& jointParamsArray, btTypedConstraint** constraints, int iBegin, int iEnd, const btContactSolverInfo& infoGlobal ); - - // parameters to control batching - static bool s_allowNestedParallelForLoops; // whether to allow nested parallel operations - static int s_minimumContactManifoldsForBatching; // don't even try to batch if fewer manifolds than this - static btBatchedConstraints::BatchingMethod s_contactBatchingMethod; - static btBatchedConstraints::BatchingMethod s_jointBatchingMethod; - static int s_minBatchSize; // desired number of constraints per batch - static int s_maxBatchSize; - -protected: - static const int CACHE_LINE_SIZE = 64; - - btBatchedConstraints m_batchedContactConstraints; - btBatchedConstraints m_batchedJointConstraints; - int m_numFrictionDirections; - bool m_useBatching; - bool m_useObsoleteJointConstraints; - btAlignedObjectArray m_manifoldCachedInfoArray; - btAlignedObjectArray m_rollingFrictionIndexTable; // lookup table mapping contact index to rolling friction index - btSpinMutex m_bodySolverArrayMutex; - char m_antiFalseSharingPadding[CACHE_LINE_SIZE]; // padding to keep mutexes in separate cachelines - btSpinMutex m_kinematicBodyUniqueIdToSolverBodyTableMutex; - btAlignedObjectArray m_scratchMemory; - - virtual void randomizeConstraintOrdering( int iteration, int numIterations ); - virtual btScalar resolveAllJointConstraints( int iteration ); - virtual btScalar resolveAllContactConstraints(); - virtual btScalar resolveAllContactFrictionConstraints(); - virtual btScalar resolveAllContactConstraintsInterleaved(); - virtual btScalar resolveAllRollingFrictionConstraints(); - - virtual void setupBatchedContactConstraints(); - virtual void setupBatchedJointConstraints(); - virtual void convertJoints(btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal) BT_OVERRIDE; - virtual void convertContacts(btPersistentManifold** manifoldPtr, int numManifolds, const btContactSolverInfo& infoGlobal) BT_OVERRIDE; - virtual void convertBodies(btCollisionObject** bodies, int numBodies, const btContactSolverInfo& infoGlobal) BT_OVERRIDE; - - int getOrInitSolverBodyThreadsafe(btCollisionObject& body, btScalar timeStep); - void allocAllContactConstraints(btPersistentManifold** manifoldPtr, int numManifolds, const btContactSolverInfo& infoGlobal); - void setupAllContactConstraints(const btContactSolverInfo& infoGlobal); - void randomizeBatchedConstraintOrdering( btBatchedConstraints* batchedConstraints ); - -public: - - BT_DECLARE_ALIGNED_ALLOCATOR(); - - btSequentialImpulseConstraintSolverMt(); - virtual ~btSequentialImpulseConstraintSolverMt(); - - btScalar resolveMultipleJointConstraints( const btAlignedObjectArray& consIndices, int batchBegin, int batchEnd, int iteration ); - btScalar resolveMultipleContactConstraints( const btAlignedObjectArray& consIndices, int batchBegin, int batchEnd ); - btScalar resolveMultipleContactSplitPenetrationImpulseConstraints( const btAlignedObjectArray& consIndices, int batchBegin, int batchEnd ); - btScalar resolveMultipleContactFrictionConstraints( const btAlignedObjectArray& consIndices, int batchBegin, int batchEnd ); - btScalar resolveMultipleContactRollingFrictionConstraints( const btAlignedObjectArray& consIndices, int batchBegin, int batchEnd ); - btScalar resolveMultipleContactConstraintsInterleaved( const btAlignedObjectArray& contactIndices, int batchBegin, int batchEnd ); - - void internalCollectContactManifoldCachedInfo(btContactManifoldCachedInfo* cachedInfoArray, btPersistentManifold** manifoldPtr, int numManifolds, const btContactSolverInfo& infoGlobal); - void internalAllocContactConstraints(const btContactManifoldCachedInfo* cachedInfoArray, int numManifolds); - void internalSetupContactConstraints(int iContactConstraint, const btContactSolverInfo& infoGlobal); - void internalConvertBodies(btCollisionObject** bodies, int iBegin, int iEnd, const btContactSolverInfo& infoGlobal); - void internalWriteBackContacts(int iBegin, int iEnd, const btContactSolverInfo& infoGlobal); - void internalWriteBackJoints(int iBegin, int iEnd, const btContactSolverInfo& infoGlobal); - void internalWriteBackBodies(int iBegin, int iEnd, const btContactSolverInfo& infoGlobal); -}; - - - - -#endif //BT_SEQUENTIAL_IMPULSE_CONSTRAINT_SOLVER_MT_H - diff --git a/extern/bullet/src/BulletDynamics/ConstraintSolver/btSolverBody.h b/extern/bullet/src/BulletDynamics/ConstraintSolver/btSolverBody.h index 27ccefe41690..8e4456e617aa 100644 --- a/extern/bullet/src/BulletDynamics/ConstraintSolver/btSolverBody.h +++ b/extern/bullet/src/BulletDynamics/ConstraintSolver/btSolverBody.h @@ -37,8 +37,13 @@ struct btSimdScalar { } - +/* workaround for clang 3.4 ( == apple clang 5.1 ) issue, friction would fail with forced inlining */ +#if (defined(__clang__) && defined(__apple_build_version__) && (__clang_major__ == 5) && (__clang_minor__ == 1)) \ +|| (defined(__clang__) && !defined(__apple_build_version__) && (__clang_major__ == 3) && (__clang_minor__ == 4)) + inline __attribute__ ((noinline)) btSimdScalar(float fl) +#else SIMD_FORCE_INLINE btSimdScalar(float fl) +#endif :m_vec128 (_mm_set1_ps(fl)) { } diff --git a/extern/bullet/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp b/extern/bullet/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp index b9944c138b05..fc85b4f8626f 100644 --- a/extern/bullet/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp +++ b/extern/bullet/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp @@ -842,9 +842,6 @@ class btClosestNotMeConvexResultCallback : public btCollisionWorld::ClosestConve btCollisionObject* otherObj = (btCollisionObject*) proxy0->m_clientObject; - if(!m_dispatcher->needsCollision(m_me, otherObj)) - return false; - //call needsResponse, see http://code.google.com/p/bullet/issues/detail?id=179 if (m_dispatcher->needsResponse(m_me,otherObj)) { @@ -955,7 +952,7 @@ void btDiscreteDynamicsWorld::createPredictiveContactsInternal( btRigidBody** bo int index = manifold->addManifoldPoint(newPoint, isPredictive); btManifoldPoint& pt = manifold->getContactPoint(index); pt.m_combinedRestitution = 0; - pt.m_combinedFriction = gCalculateCombinedFrictionCallback(body,sweepResults.m_hitCollisionObject); + pt.m_combinedFriction = btManifoldResult::calculateCombinedFriction(body,sweepResults.m_hitCollisionObject); pt.m_positionWorldOnA = body->getWorldTransform().getOrigin(); pt.m_positionWorldOnB = worldPointB; @@ -1116,7 +1113,7 @@ void btDiscreteDynamicsWorld::integrateTransforms(btScalar timeStep) for (int p=0;pgetNumContacts();p++) { const btManifoldPoint& pt = manifold->getContactPoint(p); - btScalar combinedRestitution = gCalculateCombinedRestitutionCallback(body0, body1); + btScalar combinedRestitution = btManifoldResult::calculateCombinedRestitution(body0, body1); if (combinedRestitution>0 && pt.m_appliedImpulse != 0.f) //if (pt.getDistance()>0 && combinedRestitution>0 && pt.m_appliedImpulse != 0.f) @@ -1345,12 +1342,9 @@ void btDiscreteDynamicsWorld::debugDrawConstraint(btTypedConstraint* constraint) btVector3 axis = tr.getBasis().getColumn(0); btScalar minTh = p6DOF->getRotationalLimitMotor(1)->m_loLimit; btScalar maxTh = p6DOF->getRotationalLimitMotor(1)->m_hiLimit; - if (minTh <= maxTh) - { - btScalar minPs = p6DOF->getRotationalLimitMotor(2)->m_loLimit; - btScalar maxPs = p6DOF->getRotationalLimitMotor(2)->m_hiLimit; - getDebugDrawer()->drawSpherePatch(center, up, axis, dbgDrawSize * btScalar(.9f), minTh, maxTh, minPs, maxPs, btVector3(0, 0, 0)); - } + btScalar minPs = p6DOF->getRotationalLimitMotor(2)->m_loLimit; + btScalar maxPs = p6DOF->getRotationalLimitMotor(2)->m_hiLimit; + getDebugDrawer()->drawSpherePatch(center, up, axis, dbgDrawSize * btScalar(.9f), minTh, maxTh, minPs, maxPs, btVector3(0, 0, 0)); axis = tr.getBasis().getColumn(1); btScalar ay = p6DOF->getAngle(1); btScalar az = p6DOF->getAngle(2); @@ -1539,8 +1533,6 @@ void btDiscreteDynamicsWorld::serialize(btSerializer* serializer) serializeRigidBodies(serializer); - serializeContactManifolds(serializer); - serializer->finishSerialization(); } diff --git a/extern/bullet/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorldMt.cpp b/extern/bullet/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorldMt.cpp index d705bf238174..1d10bad9221d 100644 --- a/extern/bullet/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorldMt.cpp +++ b/extern/bullet/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorldMt.cpp @@ -50,6 +50,63 @@ subject to the following restrictions: #include "LinearMath/btSerializer.h" +struct InplaceSolverIslandCallbackMt : public btSimulationIslandManagerMt::IslandCallback +{ + btContactSolverInfo* m_solverInfo; + btConstraintSolver* m_solver; + btIDebugDraw* m_debugDrawer; + btDispatcher* m_dispatcher; + + InplaceSolverIslandCallbackMt( + btConstraintSolver* solver, + btStackAlloc* stackAlloc, + btDispatcher* dispatcher) + :m_solverInfo(NULL), + m_solver(solver), + m_debugDrawer(NULL), + m_dispatcher(dispatcher) + { + + } + + InplaceSolverIslandCallbackMt& operator=(InplaceSolverIslandCallbackMt& other) + { + btAssert(0); + (void)other; + return *this; + } + + SIMD_FORCE_INLINE void setup ( btContactSolverInfo* solverInfo, btIDebugDraw* debugDrawer) + { + btAssert(solverInfo); + m_solverInfo = solverInfo; + m_debugDrawer = debugDrawer; + } + + + virtual void processIsland( btCollisionObject** bodies, + int numBodies, + btPersistentManifold** manifolds, + int numManifolds, + btTypedConstraint** constraints, + int numConstraints, + int islandId + ) + { + m_solver->solveGroup( bodies, + numBodies, + manifolds, + numManifolds, + constraints, + numConstraints, + *m_solverInfo, + m_debugDrawer, + m_dispatcher + ); + } + +}; + /// /// btConstraintSolverPoolMt @@ -152,12 +209,7 @@ void btConstraintSolverPoolMt::reset() /// btDiscreteDynamicsWorldMt /// -btDiscreteDynamicsWorldMt::btDiscreteDynamicsWorldMt(btDispatcher* dispatcher, - btBroadphaseInterface* pairCache, - btConstraintSolverPoolMt* constraintSolver, - btConstraintSolver* constraintSolverMt, - btCollisionConfiguration* collisionConfiguration -) +btDiscreteDynamicsWorldMt::btDiscreteDynamicsWorldMt(btDispatcher* dispatcher, btBroadphaseInterface* pairCache, btConstraintSolverPoolMt* constraintSolver, btCollisionConfiguration* collisionConfiguration) : btDiscreteDynamicsWorld(dispatcher,pairCache,constraintSolver,collisionConfiguration) { if (m_ownsIslandManager) @@ -165,18 +217,31 @@ btDiscreteDynamicsWorldMt::btDiscreteDynamicsWorldMt(btDispatcher* dispatcher, m_islandManager->~btSimulationIslandManager(); btAlignedFree( m_islandManager); } + { + void* mem = btAlignedAlloc(sizeof(InplaceSolverIslandCallbackMt),16); + m_solverIslandCallbackMt = new (mem) InplaceSolverIslandCallbackMt (m_constraintSolver, 0, dispatcher); + } { void* mem = btAlignedAlloc(sizeof(btSimulationIslandManagerMt),16); btSimulationIslandManagerMt* im = new (mem) btSimulationIslandManagerMt(); im->setMinimumSolverBatchSize( m_solverInfo.m_minimumSolverBatchSize ); m_islandManager = im; } - m_constraintSolverMt = constraintSolverMt; } btDiscreteDynamicsWorldMt::~btDiscreteDynamicsWorldMt() { + if (m_solverIslandCallbackMt) + { + m_solverIslandCallbackMt->~InplaceSolverIslandCallbackMt(); + btAlignedFree(m_solverIslandCallbackMt); + } + if (m_ownsConstraintSolver) + { + m_constraintSolver->~btConstraintSolver(); + btAlignedFree(m_constraintSolver); + } } @@ -184,17 +249,12 @@ void btDiscreteDynamicsWorldMt::solveConstraints(btContactSolverInfo& solverInfo { BT_PROFILE("solveConstraints"); + m_solverIslandCallbackMt->setup(&solverInfo, getDebugDrawer()); m_constraintSolver->prepareSolve(getCollisionWorld()->getNumCollisionObjects(), getCollisionWorld()->getDispatcher()->getNumManifolds()); /// solve all the constraints for this island btSimulationIslandManagerMt* im = static_cast(m_islandManager); - btSimulationIslandManagerMt::SolverParams solverParams; - solverParams.m_solverPool = m_constraintSolver; - solverParams.m_solverMt = m_constraintSolverMt; - solverParams.m_solverInfo = &solverInfo; - solverParams.m_debugDrawer = m_debugDrawer; - solverParams.m_dispatcher = getCollisionWorld()->getDispatcher(); - im->buildAndProcessIslands( getCollisionWorld()->getDispatcher(), getCollisionWorld(), m_constraints, solverParams ); + im->buildAndProcessIslands( getCollisionWorld()->getDispatcher(), getCollisionWorld(), m_constraints, m_solverIslandCallbackMt ); m_constraintSolver->allSolved(solverInfo, m_debugDrawer); } @@ -265,14 +325,3 @@ void btDiscreteDynamicsWorldMt::integrateTransforms( btScalar timeStep ) } } - -int btDiscreteDynamicsWorldMt::stepSimulation( btScalar timeStep, int maxSubSteps, btScalar fixedTimeStep ) -{ - int numSubSteps = btDiscreteDynamicsWorld::stepSimulation(timeStep, maxSubSteps, fixedTimeStep); - if (btITaskScheduler* scheduler = btGetTaskScheduler()) - { - // tell Bullet's threads to sleep, so other threads can run - scheduler->sleepWorkerThreadsHint(); - } - return numSubSteps; -} diff --git a/extern/bullet/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorldMt.h b/extern/bullet/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorldMt.h index 667fe5800e51..2f144cdda4c9 100644 --- a/extern/bullet/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorldMt.h +++ b/extern/bullet/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorldMt.h @@ -21,6 +21,7 @@ subject to the following restrictions: #include "btSimulationIslandManagerMt.h" #include "BulletDynamics/ConstraintSolver/btConstraintSolver.h" +struct InplaceSolverIslandCallbackMt; /// /// btConstraintSolverPoolMt - masquerades as a constraint solver, but really it is a threadsafe pool of them. @@ -87,7 +88,7 @@ class btConstraintSolverPoolMt : public btConstraintSolver ATTRIBUTE_ALIGNED16(class) btDiscreteDynamicsWorldMt : public btDiscreteDynamicsWorld { protected: - btConstraintSolver* m_constraintSolverMt; + InplaceSolverIslandCallbackMt* m_solverIslandCallbackMt; virtual void solveConstraints(btContactSolverInfo& solverInfo) BT_OVERRIDE; @@ -125,12 +126,9 @@ ATTRIBUTE_ALIGNED16(class) btDiscreteDynamicsWorldMt : public btDiscreteDynamics btDiscreteDynamicsWorldMt(btDispatcher* dispatcher, btBroadphaseInterface* pairCache, btConstraintSolverPoolMt* constraintSolver, // Note this should be a solver-pool for multi-threading - btConstraintSolver* constraintSolverMt, // single multi-threaded solver for large islands (or NULL) btCollisionConfiguration* collisionConfiguration ); virtual ~btDiscreteDynamicsWorldMt(); - - virtual int stepSimulation( btScalar timeStep, int maxSubSteps, btScalar fixedTimeStep ) BT_OVERRIDE; }; #endif //BT_DISCRETE_DYNAMICS_WORLD_H diff --git a/extern/bullet/src/BulletDynamics/Dynamics/btRigidBody.cpp b/extern/bullet/src/BulletDynamics/Dynamics/btRigidBody.cpp index ca0714fcfa86..a9f274962120 100644 --- a/extern/bullet/src/BulletDynamics/Dynamics/btRigidBody.cpp +++ b/extern/bullet/src/BulletDynamics/Dynamics/btRigidBody.cpp @@ -427,50 +427,38 @@ void btRigidBody::setCenterOfMassTransform(const btTransform& xform) } +bool btRigidBody::checkCollideWithOverride(const btCollisionObject* co) const +{ + const btRigidBody* otherRb = btRigidBody::upcast(co); + if (!otherRb) + return true; + + for (int i = 0; i < m_constraintRefs.size(); ++i) + { + const btTypedConstraint* c = m_constraintRefs[i]; + if (c->isEnabled()) + if (&c->getRigidBodyA() == otherRb || &c->getRigidBodyB() == otherRb) + return false; + } + + return true; +} void btRigidBody::addConstraintRef(btTypedConstraint* c) { - ///disable collision with the 'other' body - int index = m_constraintRefs.findLinearSearch(c); - //don't add constraints that are already referenced - //btAssert(index == m_constraintRefs.size()); if (index == m_constraintRefs.size()) - { - m_constraintRefs.push_back(c); - btCollisionObject* colObjA = &c->getRigidBodyA(); - btCollisionObject* colObjB = &c->getRigidBodyB(); - if (colObjA == this) - { - colObjA->setIgnoreCollisionCheck(colObjB, true); - } - else - { - colObjB->setIgnoreCollisionCheck(colObjA, true); - } - } + m_constraintRefs.push_back(c); + + m_checkCollideWith = true; } void btRigidBody::removeConstraintRef(btTypedConstraint* c) { - int index = m_constraintRefs.findLinearSearch(c); - //don't remove constraints that are not referenced - if(index < m_constraintRefs.size()) - { - m_constraintRefs.remove(c); - btCollisionObject* colObjA = &c->getRigidBodyA(); - btCollisionObject* colObjB = &c->getRigidBodyB(); - if (colObjA == this) - { - colObjA->setIgnoreCollisionCheck(colObjB, false); - } - else - { - colObjB->setIgnoreCollisionCheck(colObjA, false); - } - } + m_constraintRefs.remove(c); + m_checkCollideWith = m_constraintRefs.size() > 0; } int btRigidBody::calculateSerializeBufferSize() const diff --git a/extern/bullet/src/BulletDynamics/Dynamics/btRigidBody.h b/extern/bullet/src/BulletDynamics/Dynamics/btRigidBody.h index 372245031b14..dbbf9958618c 100644 --- a/extern/bullet/src/BulletDynamics/Dynamics/btRigidBody.h +++ b/extern/bullet/src/BulletDynamics/Dynamics/btRigidBody.h @@ -512,6 +512,8 @@ class btRigidBody : public btCollisionObject return (getBroadphaseProxy() != 0); } + virtual bool checkCollideWithOverride(const btCollisionObject* co) const; + void addConstraintRef(btTypedConstraint* c); void removeConstraintRef(btTypedConstraint* c); diff --git a/extern/bullet/src/BulletDynamics/Dynamics/btSimulationIslandManagerMt.cpp b/extern/bullet/src/BulletDynamics/Dynamics/btSimulationIslandManagerMt.cpp index fc54f0ba6eab..99b34353c781 100644 --- a/extern/bullet/src/BulletDynamics/Dynamics/btSimulationIslandManagerMt.cpp +++ b/extern/bullet/src/BulletDynamics/Dynamics/btSimulationIslandManagerMt.cpp @@ -22,7 +22,6 @@ subject to the following restrictions: #include "BulletCollision/CollisionDispatch/btCollisionObject.h" #include "BulletCollision/CollisionDispatch/btCollisionWorld.h" #include "BulletDynamics/ConstraintSolver/btTypedConstraint.h" -#include "BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.h" // for s_minimumContactManifoldsForBatching //#include #include "LinearMath/btQuickprof.h" @@ -276,7 +275,7 @@ btSimulationIslandManagerMt::Island* btSimulationIslandManagerMt::allocateIsland void btSimulationIslandManagerMt::buildIslands( btDispatcher* dispatcher, btCollisionWorld* collisionWorld ) { - BT_PROFILE("buildIslands"); + BT_PROFILE("islandUnionFindAndQuickSort"); btCollisionObjectArray& collisionObjects = collisionWorld->getCollisionObjectArray(); @@ -315,11 +314,13 @@ void btSimulationIslandManagerMt::buildIslands( btDispatcher* dispatcher, btColl btAssert((colObj0->getIslandTag() == islandId) || (colObj0->getIslandTag() == -1)); if (colObj0->getIslandTag() == islandId) { - if (colObj0->getActivationState()== ACTIVE_TAG || - colObj0->getActivationState()== DISABLE_DEACTIVATION) + if (colObj0->getActivationState()== ACTIVE_TAG) + { + allSleeping = false; + } + if (colObj0->getActivationState()== DISABLE_DEACTIVATION) { allSleeping = false; - break; } } } @@ -545,103 +546,59 @@ void btSimulationIslandManagerMt::mergeIslands() } -void btSimulationIslandManagerMt::solveIsland(btConstraintSolver* solver, Island& island, const SolverParams& solverParams) -{ - btPersistentManifold** manifolds = island.manifoldArray.size() ? &island.manifoldArray[ 0 ] : NULL; - btTypedConstraint** constraintsPtr = island.constraintArray.size() ? &island.constraintArray[ 0 ] : NULL; - solver->solveGroup( &island.bodyArray[ 0 ], - island.bodyArray.size(), - manifolds, - island.manifoldArray.size(), - constraintsPtr, - island.constraintArray.size(), - *solverParams.m_solverInfo, - solverParams.m_debugDrawer, - solverParams.m_dispatcher - ); -} - - -void btSimulationIslandManagerMt::serialIslandDispatch( btAlignedObjectArray* islandsPtr, const SolverParams& solverParams ) +void btSimulationIslandManagerMt::serialIslandDispatch( btAlignedObjectArray* islandsPtr, IslandCallback* callback ) { BT_PROFILE( "serialIslandDispatch" ); // serial dispatch btAlignedObjectArray& islands = *islandsPtr; - btConstraintSolver* solver = solverParams.m_solverMt ? solverParams.m_solverMt : solverParams.m_solverPool; for ( int i = 0; i < islands.size(); ++i ) { - solveIsland(solver, *islands[ i ], solverParams); + Island* island = islands[ i ]; + btPersistentManifold** manifolds = island->manifoldArray.size() ? &island->manifoldArray[ 0 ] : NULL; + btTypedConstraint** constraintsPtr = island->constraintArray.size() ? &island->constraintArray[ 0 ] : NULL; + callback->processIsland( &island->bodyArray[ 0 ], + island->bodyArray.size(), + manifolds, + island->manifoldArray.size(), + constraintsPtr, + island->constraintArray.size(), + island->id + ); } } - struct UpdateIslandDispatcher : public btIParallelForBody { - btAlignedObjectArray& m_islandsPtr; - const btSimulationIslandManagerMt::SolverParams& m_solverParams; - - UpdateIslandDispatcher(btAlignedObjectArray& islandsPtr, const btSimulationIslandManagerMt::SolverParams& solverParams) - : m_islandsPtr(islandsPtr), m_solverParams(solverParams) - {} + btAlignedObjectArray* islandsPtr; + btSimulationIslandManagerMt::IslandCallback* callback; void forLoop( int iBegin, int iEnd ) const BT_OVERRIDE { - btConstraintSolver* solver = m_solverParams.m_solverPool; for ( int i = iBegin; i < iEnd; ++i ) { - btSimulationIslandManagerMt::Island* island = m_islandsPtr[ i ]; - btSimulationIslandManagerMt::solveIsland( solver, *island, m_solverParams ); + btSimulationIslandManagerMt::Island* island = ( *islandsPtr )[ i ]; + btPersistentManifold** manifolds = island->manifoldArray.size() ? &island->manifoldArray[ 0 ] : NULL; + btTypedConstraint** constraintsPtr = island->constraintArray.size() ? &island->constraintArray[ 0 ] : NULL; + callback->processIsland( &island->bodyArray[ 0 ], + island->bodyArray.size(), + manifolds, + island->manifoldArray.size(), + constraintsPtr, + island->constraintArray.size(), + island->id + ); } } }; - -void btSimulationIslandManagerMt::parallelIslandDispatch( btAlignedObjectArray* islandsPtr, const SolverParams& solverParams ) +void btSimulationIslandManagerMt::parallelIslandDispatch( btAlignedObjectArray* islandsPtr, IslandCallback* callback ) { BT_PROFILE( "parallelIslandDispatch" ); - // - // if there are islands with many contacts, it may be faster to submit these - // large islands *serially* to a single parallel constraint solver, and then later - // submit the remaining smaller islands in parallel to multiple sequential solvers. - // - // Some task schedulers do not deal well with nested parallelFor loops. One implementation - // of OpenMP was actually slower than doing everything single-threaded. Intel TBB - // on the other hand, seems to do a pretty respectable job with it. - // - // When solving islands in parallel, the worst case performance happens when there - // is one very large island and then perhaps a smattering of very small - // islands -- one worker thread takes the large island and the remaining workers - // tear through the smaller islands and then sit idle waiting for the first worker - // to finish. Solving islands in parallel works best when there are numerous small - // islands, roughly equal in size. - // - // By contrast, the other approach -- the parallel constraint solver -- is only - // able to deliver a worthwhile speedup when the island is large. For smaller islands, - // it is difficult to extract a useful amount of parallelism -- the overhead of grouping - // the constraints into batches and sending the batches to worker threads can nullify - // any gains from parallelism. - // - - UpdateIslandDispatcher dispatcher(*islandsPtr, solverParams); - // We take advantage of the fact the islands are sorted in order of decreasing size - int iBegin = 0; - if (solverParams.m_solverMt) - { - while ( iBegin < islandsPtr->size() ) - { - btSimulationIslandManagerMt::Island* island = ( *islandsPtr )[ iBegin ]; - if ( island->manifoldArray.size() < btSequentialImpulseConstraintSolverMt::s_minimumContactManifoldsForBatching ) - { - // OK to submit the rest of the array in parallel - break; - } - // serial dispatch to parallel solver for large islands (if any) - solveIsland(solverParams.m_solverMt, *island, solverParams); - ++iBegin; - } - } - // parallel dispatch to sequential solvers for rest - btParallelFor( iBegin, islandsPtr->size(), 1, dispatcher ); + int grainSize = 1; // iterations per task + UpdateIslandDispatcher dispatcher; + dispatcher.islandsPtr = islandsPtr; + dispatcher.callback = callback; + btParallelFor( 0, islandsPtr->size(), grainSize, dispatcher ); } @@ -649,14 +606,15 @@ void btSimulationIslandManagerMt::parallelIslandDispatch( btAlignedObjectArray& constraints, - const SolverParams& solverParams + IslandCallback* callback ) { - BT_PROFILE("buildAndProcessIslands"); btCollisionObjectArray& collisionObjects = collisionWorld->getCollisionObjectArray(); buildIslands(dispatcher,collisionWorld); + BT_PROFILE("processIslands"); + if(!getSplitIslands()) { btPersistentManifold** manifolds = dispatcher->getInternalManifoldPointer(); @@ -688,17 +646,14 @@ void btSimulationIslandManagerMt::buildAndProcessIslands( btDispatcher* dispatch } } btTypedConstraint** constraintsPtr = constraints.size() ? &constraints[ 0 ] : NULL; - btConstraintSolver* solver = solverParams.m_solverMt ? solverParams.m_solverMt : solverParams.m_solverPool; - solver->solveGroup(&collisionObjects[0], - collisionObjects.size(), - manifolds, - maxNumManifolds, - constraintsPtr, - constraints.size(), - *solverParams.m_solverInfo, - solverParams.m_debugDrawer, - solverParams.m_dispatcher - ); + callback->processIsland(&collisionObjects[0], + collisionObjects.size(), + manifolds, + maxNumManifolds, + constraintsPtr, + constraints.size(), + -1 + ); } else { @@ -718,6 +673,6 @@ void btSimulationIslandManagerMt::buildAndProcessIslands( btDispatcher* dispatch mergeIslands(); } // dispatch islands to solver - m_islandDispatch( &m_activeIslands, solverParams ); + m_islandDispatch( &m_activeIslands, callback ); } } diff --git a/extern/bullet/src/BulletDynamics/Dynamics/btSimulationIslandManagerMt.h b/extern/bullet/src/BulletDynamics/Dynamics/btSimulationIslandManagerMt.h index 563577a6f430..9a781aaef16e 100644 --- a/extern/bullet/src/BulletDynamics/Dynamics/btSimulationIslandManagerMt.h +++ b/extern/bullet/src/BulletDynamics/Dynamics/btSimulationIslandManagerMt.h @@ -19,9 +19,7 @@ subject to the following restrictions: #include "BulletCollision/CollisionDispatch/btSimulationIslandManager.h" class btTypedConstraint; -class btConstraintSolver; -struct btContactSolverInfo; -class btIDebugDraw; + /// /// SimulationIslandManagerMt -- Multithread capable version of SimulationIslandManager @@ -47,19 +45,22 @@ class btSimulationIslandManagerMt : public btSimulationIslandManager void append( const Island& other ); // add bodies, manifolds, constraints to my own }; - struct SolverParams + struct IslandCallback { - btConstraintSolver* m_solverPool; - btConstraintSolver* m_solverMt; - btContactSolverInfo* m_solverInfo; - btIDebugDraw* m_debugDrawer; - btDispatcher* m_dispatcher; - }; - static void solveIsland(btConstraintSolver* solver, Island& island, const SolverParams& solverParams); + virtual ~IslandCallback() {}; - typedef void( *IslandDispatchFunc ) ( btAlignedObjectArray* islands, const SolverParams& solverParams ); - static void serialIslandDispatch( btAlignedObjectArray* islandsPtr, const SolverParams& solverParams ); - static void parallelIslandDispatch( btAlignedObjectArray* islandsPtr, const SolverParams& solverParams ); + virtual void processIsland( btCollisionObject** bodies, + int numBodies, + btPersistentManifold** manifolds, + int numManifolds, + btTypedConstraint** constraints, + int numConstraints, + int islandId + ) = 0; + }; + typedef void( *IslandDispatchFunc ) ( btAlignedObjectArray* islands, IslandCallback* callback ); + static void serialIslandDispatch( btAlignedObjectArray* islandsPtr, IslandCallback* callback ); + static void parallelIslandDispatch( btAlignedObjectArray* islandsPtr, IslandCallback* callback ); protected: btAlignedObjectArray m_allocatedIslands; // owner of all Islands btAlignedObjectArray m_activeIslands; // islands actively in use @@ -82,11 +83,7 @@ class btSimulationIslandManagerMt : public btSimulationIslandManager btSimulationIslandManagerMt(); virtual ~btSimulationIslandManagerMt(); - virtual void buildAndProcessIslands( btDispatcher* dispatcher, - btCollisionWorld* collisionWorld, - btAlignedObjectArray& constraints, - const SolverParams& solverParams - ); + virtual void buildAndProcessIslands( btDispatcher* dispatcher, btCollisionWorld* collisionWorld, btAlignedObjectArray& constraints, IslandCallback* callback ); virtual void buildIslands(btDispatcher* dispatcher,btCollisionWorld* colWorld); @@ -109,6 +106,5 @@ class btSimulationIslandManagerMt : public btSimulationIslandManager } }; - #endif //BT_SIMULATION_ISLAND_MANAGER_H diff --git a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBody.cpp b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBody.cpp index 34fe4b8de82e..036b226e8dbc 100644 --- a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBody.cpp +++ b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBody.cpp @@ -112,15 +112,14 @@ btMultiBody::btMultiBody(int n_links, m_userObjectPointer(0), m_userIndex2(-1), m_userIndex(-1), - m_companionId(-1), m_linearDamping(0.04f), m_angularDamping(0.04f), m_useGyroTerm(true), - m_maxAppliedImpulse(1000.f), + m_maxAppliedImpulse(1000.f), m_maxCoordinateVelocity(100.f), - m_hasSelfCollision(true), + m_hasSelfCollision(true), __posUpdated(false), - m_dofCount(0), + m_dofCount(0), m_posVarCnt(0), m_useRK4(false), m_useGlobalVelocities(false), @@ -137,9 +136,6 @@ btMultiBody::btMultiBody(int n_links, m_baseForce.setValue(0, 0, 0); m_baseTorque.setValue(0, 0, 0); - - clearConstraintForces(); - clearForcesAndTorques(); } btMultiBody::~btMultiBody() @@ -349,10 +345,7 @@ void btMultiBody::finalizeMultiDof() m_deltaV.resize(6 + m_dofCount); m_realBuf.resize(6 + m_dofCount + m_dofCount*m_dofCount + 6 + m_dofCount); //m_dofCount for joint-space vels + m_dofCount^2 for "D" matrices + delta-pos vector (6 base "vels" + joint "vels") m_vectorBuf.resize(2 * m_dofCount); //two 3-vectors (i.e. one six-vector) for each system dof ("h" matrices) - for (int i=0;i 2 x m_dofCount + scratch_r.resize(2*m_dofCount + 6); //multidof? ("Y"s use it and it is used to store qdd) => 2 x m_dofCount scratch_v.resize(8*num_links + 6); scratch_m.resize(4*num_links + 4); @@ -781,7 +774,7 @@ void btMultiBody::computeAccelerationsArticulatedBodyAlgorithmMultiDof(btScalar // hhat is NOT stored for the base (but ahat is) btSpatialForceVector * h = (btSpatialForceVector *)(m_dofCount > 0 ? &m_vectorBuf[0] : 0); btSpatialMotionVector * spatAcc = (btSpatialMotionVector *)v_ptr; - v_ptr += num_links * 2 + 2; + v_ptr += num_links * 2 + 2; // // Y_i, invD_i btScalar * invD = m_dofCount > 0 ? &m_realBuf[6 + m_dofCount] : 0; @@ -819,13 +812,13 @@ void btMultiBody::computeAccelerationsArticulatedBodyAlgorithmMultiDof(btScalar } else { - const btVector3& baseForce = isConstraintPass? m_baseConstraintForce : m_baseForce; - const btVector3& baseTorque = isConstraintPass? m_baseConstraintTorque : m_baseTorque; + btVector3 baseForce = isConstraintPass? m_baseConstraintForce : m_baseForce; + btVector3 baseTorque = isConstraintPass? m_baseConstraintTorque : m_baseTorque; //external forces zeroAccSpatFrc[0].setVector(-(rot_from_parent[0] * baseTorque), -(rot_from_parent[0] * baseForce)); //adding damping terms (only) - const btScalar linDampMult = 1., angDampMult = 1.; + btScalar linDampMult = 1., angDampMult = 1.; zeroAccSpatFrc[0].addVector(angDampMult * m_baseInertia * spatVel[0].getAngular() * (DAMPING_K1_ANGULAR + DAMPING_K2_ANGULAR * spatVel[0].getAngular().safeNorm()), linDampMult * m_baseMass * spatVel[0].getLinear() * (DAMPING_K1_LINEAR + DAMPING_K2_LINEAR * spatVel[0].getLinear().safeNorm())); @@ -967,15 +960,16 @@ void btMultiBody::computeAccelerationsArticulatedBodyAlgorithmMultiDof(btScalar // Y[m_links[i].m_dofOffset + dof] = m_links[i].m_jointTorque[dof] - m_links[i].m_axes[dof].dot(zeroAccSpatFrc[i+1]) - - spatCoriolisAcc[i].dot(hDof); - + - spatCoriolisAcc[i].dot(hDof) + ; } - for(int dof = 0; dof < m_links[i].m_dofCount; ++dof) - { - btScalar *D_row = &D[dof * m_links[i].m_dofCount]; + + for(int dof = 0; dof < m_links[i].m_dofCount; ++dof) + { + btScalar *D_row = &D[dof * m_links[i].m_dofCount]; for(int dof2 = 0; dof2 < m_links[i].m_dofCount; ++dof2) { - const btSpatialForceVector &hDof2 = h[m_links[i].m_dofOffset + dof2]; + btSpatialForceVector &hDof2 = h[m_links[i].m_dofOffset + dof2]; D_row[dof2] = m_links[i].m_axes[dof].dot(hDof2); } } @@ -986,20 +980,14 @@ void btMultiBody::computeAccelerationsArticulatedBodyAlgorithmMultiDof(btScalar case btMultibodyLink::ePrismatic: case btMultibodyLink::eRevolute: { - if (D[0]>=SIMD_EPSILON) - { - invDi[0] = 1.0f / D[0]; - } else - { - invDi[0] = 0; - } + invDi[0] = 1.0f / D[0]; break; } case btMultibodyLink::eSpherical: case btMultibodyLink::ePlanar: { - const btMatrix3x3 D3x3(D[0], D[1], D[2], D[3], D[4], D[5], D[6], D[7], D[8]); - const btMatrix3x3 invD3x3(D3x3.inverse()); + btMatrix3x3 D3x3; D3x3.setValue(D[0], D[1], D[2], D[3], D[4], D[5], D[6], D[7], D[8]); + btMatrix3x3 invD3x3; invD3x3 = D3x3.inverse(); //unroll the loop? for(int row = 0; row < 3; ++row) @@ -1025,7 +1013,7 @@ void btMultiBody::computeAccelerationsArticulatedBodyAlgorithmMultiDof(btScalar for(int dof2 = 0; dof2 < m_links[i].m_dofCount; ++dof2) { - const btSpatialForceVector &hDof2 = h[m_links[i].m_dofOffset + dof2]; + btSpatialForceVector &hDof2 = h[m_links[i].m_dofOffset + dof2]; // spatForceVecTemps[dof] += hDof2 * invDi[dof2 * m_links[i].m_dofCount + dof]; } @@ -1036,7 +1024,7 @@ void btMultiBody::computeAccelerationsArticulatedBodyAlgorithmMultiDof(btScalar //determine (h*D^{-1}) * h^{T} for(int dof = 0; dof < m_links[i].m_dofCount; ++dof) { - const btSpatialForceVector &hDof = h[m_links[i].m_dofOffset + dof]; + btSpatialForceVector &hDof = h[m_links[i].m_dofOffset + dof]; // dyadTemp -= symmetricSpatialOuterProduct(hDof, spatForceVecTemps[dof]); } @@ -1057,7 +1045,7 @@ void btMultiBody::computeAccelerationsArticulatedBodyAlgorithmMultiDof(btScalar for(int dof = 0; dof < m_links[i].m_dofCount; ++dof) { - const btSpatialForceVector &hDof = h[m_links[i].m_dofOffset + dof]; + btSpatialForceVector &hDof = h[m_links[i].m_dofOffset + dof]; // spatForceVecTemps[0] += hDof * invD_times_Y[dof]; } @@ -1108,7 +1096,7 @@ void btMultiBody::computeAccelerationsArticulatedBodyAlgorithmMultiDof(btScalar for(int dof = 0; dof < m_links[i].m_dofCount; ++dof) { - const btSpatialForceVector &hDof = h[m_links[i].m_dofOffset + dof]; + btSpatialForceVector &hDof = h[m_links[i].m_dofOffset + dof]; // Y_minus_hT_a[dof] = Y[m_links[i].m_dofOffset + dof] - spatAcc[i+1].dot(hDof); } @@ -1168,12 +1156,12 @@ void btMultiBody::computeAccelerationsArticulatedBodyAlgorithmMultiDof(btScalar } // transform base accelerations back to the world frame. - const btVector3 omegadot_out = rot_from_parent[0].transpose() * spatAcc[0].getAngular(); + btVector3 omegadot_out = rot_from_parent[0].transpose() * spatAcc[0].getAngular(); output[0] = omegadot_out[0]; output[1] = omegadot_out[1]; output[2] = omegadot_out[2]; - const btVector3 vdot_out = rot_from_parent[0].transpose() * (spatAcc[0].getLinear() + spatVel[0].getAngular().cross(spatVel[0].getLinear())); + btVector3 vdot_out = rot_from_parent[0].transpose() * (spatAcc[0].getLinear() + spatVel[0].getAngular().cross(spatVel[0].getLinear())); output[3] = vdot_out[0]; output[4] = vdot_out[1]; output[5] = vdot_out[2]; @@ -1275,29 +1263,12 @@ void btMultiBody::solveImatrix(const btVector3& rhs_top, const btVector3& rhs_bo if (num_links == 0) { // in the case of 0 m_links (i.e. a plain rigid body, not a multibody) rhs * invI is easier - - if ((m_baseInertia[0] >= SIMD_EPSILON) && (m_baseInertia[1] >= SIMD_EPSILON) && (m_baseInertia[2] >= SIMD_EPSILON)) - { - result[0] = rhs_bot[0] / m_baseInertia[0]; - result[1] = rhs_bot[1] / m_baseInertia[1]; + result[0] = rhs_bot[0] / m_baseInertia[0]; + result[1] = rhs_bot[1] / m_baseInertia[1]; result[2] = rhs_bot[2] / m_baseInertia[2]; - } else - { - result[0] = 0; - result[1] = 0; - result[2] = 0; - } - if (m_baseMass>=SIMD_EPSILON) - { - result[3] = rhs_top[0] / m_baseMass; - result[4] = rhs_top[1] / m_baseMass; - result[5] = rhs_top[2] / m_baseMass; - } else - { - result[3] = 0; - result[4] = 0; - result[5] = 0; - } + result[3] = rhs_top[0] / m_baseMass; + result[4] = rhs_top[1] / m_baseMass; + result[5] = rhs_top[2] / m_baseMass; } else { if (!m_cachedInertiaValid) @@ -1348,21 +1319,9 @@ void btMultiBody::solveImatrix(const btSpatialForceVector &rhs, btSpatialMotionV if (num_links == 0) { // in the case of 0 m_links (i.e. a plain rigid body, not a multibody) rhs * invI is easier - if ((m_baseInertia[0] >= SIMD_EPSILON) && (m_baseInertia[1] >= SIMD_EPSILON) && (m_baseInertia[2] >= SIMD_EPSILON)) - { - result.setAngular(rhs.getAngular() / m_baseInertia); - } else - { - result.setAngular(btVector3(0,0,0)); - } - if (m_baseMass>=SIMD_EPSILON) - { - result.setLinear(rhs.getLinear() / m_baseMass); - } else - { - result.setLinear(btVector3(0,0,0)); - } - } else + result.setAngular(rhs.getAngular() / m_baseInertia); + result.setLinear(rhs.getLinear() / m_baseMass); + } else { /// Special routine for calculating the inverse of a spatial inertia matrix ///the 6x6 matrix is stored as 4 blocks of 3x3 matrices @@ -1846,7 +1805,6 @@ void btMultiBody::fillConstraintJacobianMultiDof(int link, void btMultiBody::wakeUp() { - m_sleepTimer = 0; m_awake = true; } @@ -1995,11 +1953,7 @@ int btMultiBody::calculateSerializeBufferSize() const const char* btMultiBody::serialize(void* dataBuffer, class btSerializer* serializer) const { btMultiBodyData* mbd = (btMultiBodyData*) dataBuffer; - getBasePos().serialize(mbd->m_baseWorldPosition); - getWorldToBaseRot().inverse().serialize(mbd->m_baseWorldOrientation); - getBaseVel().serialize(mbd->m_baseLinearVelocity); - getBaseOmega().serialize(mbd->m_baseAngularVelocity); - + getBaseWorldTransform().serialize(mbd->m_baseWorldTransform); mbd->m_baseMass = this->getBaseMass(); getBaseInertia().serialize(mbd->m_baseInertia); { @@ -2025,12 +1979,6 @@ const char* btMultiBody::serialize(void* dataBuffer, class btSerializer* seriali memPtr->m_posVarCount = getLink(i).m_posVarCount; getLink(i).m_inertiaLocal.serialize(memPtr->m_linkInertia); - - getLink(i).m_absFrameTotVelocity.m_topVec.serialize(memPtr->m_absFrameTotVelocityTop); - getLink(i).m_absFrameTotVelocity.m_bottomVec.serialize(memPtr->m_absFrameTotVelocityBottom); - getLink(i).m_absFrameLocVelocity.m_topVec.serialize(memPtr->m_absFrameLocVelocityTop); - getLink(i).m_absFrameLocVelocity.m_bottomVec.serialize(memPtr->m_absFrameLocVelocityBottom); - memPtr->m_linkMass = getLink(i).m_mass; memPtr->m_parentIndex = getLink(i).m_parent; memPtr->m_jointDamping = getLink(i).m_jointDamping; @@ -2040,7 +1988,7 @@ const char* btMultiBody::serialize(void* dataBuffer, class btSerializer* seriali memPtr->m_jointMaxForce = getLink(i).m_jointMaxForce; memPtr->m_jointMaxVelocity = getLink(i).m_jointMaxVelocity; - getLink(i).m_eVector.serialize(memPtr->m_parentComToThisPivotOffset); + getLink(i).m_eVector.serialize(memPtr->m_parentComToThisComOffset); getLink(i).m_dVector.serialize(memPtr->m_thisPivotToThisComOffset); getLink(i).m_zeroRotParentToThis.serialize(memPtr->m_zeroRotParentToThis); btAssert(memPtr->m_dofCount<=3); diff --git a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBody.h b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBody.h index 23ea5533f817..ac5f0993e9cb 100644 --- a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBody.h +++ b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBody.h @@ -702,18 +702,15 @@ void addJointTorque(int i, btScalar Q); int m_companionId; btScalar m_linearDamping; btScalar m_angularDamping; - bool m_useGyroTerm; + bool m_useGyroTerm; btScalar m_maxAppliedImpulse; btScalar m_maxCoordinateVelocity; bool m_hasSelfCollision; - bool __posUpdated; - int m_dofCount, m_posVarCnt; - + bool __posUpdated; + int m_dofCount, m_posVarCnt; bool m_useRK4, m_useGlobalVelocities; - //for global velocities, see 8.3.2B Proposed resolution in Jakub Stepien PhD Thesis - //https://drive.google.com/file/d/0Bz3vEa19XOYGNWdZWGpMdUdqVmZ5ZVBOaEh4ZnpNaUxxZFNV/view?usp=sharing - + ///the m_needsJointFeedback gets updated/computed during the stepVelocitiesMultiDof and it for internal usage only bool m_internalNeedsJointFeedback; }; @@ -721,17 +718,12 @@ void addJointTorque(int i, btScalar Q); struct btMultiBodyLinkDoubleData { btQuaternionDoubleData m_zeroRotParentToThis; - btVector3DoubleData m_parentComToThisPivotOffset; + btVector3DoubleData m_parentComToThisComOffset; btVector3DoubleData m_thisPivotToThisComOffset; btVector3DoubleData m_jointAxisTop[6]; btVector3DoubleData m_jointAxisBottom[6]; btVector3DoubleData m_linkInertia; // inertia of the base (in local frame; diagonal) - btVector3DoubleData m_absFrameTotVelocityTop; - btVector3DoubleData m_absFrameTotVelocityBottom; - btVector3DoubleData m_absFrameLocVelocityTop; - btVector3DoubleData m_absFrameLocVelocityBottom; - double m_linkMass; int m_parentIndex; int m_jointType; @@ -759,16 +751,11 @@ struct btMultiBodyLinkDoubleData struct btMultiBodyLinkFloatData { btQuaternionFloatData m_zeroRotParentToThis; - btVector3FloatData m_parentComToThisPivotOffset; + btVector3FloatData m_parentComToThisComOffset; btVector3FloatData m_thisPivotToThisComOffset; btVector3FloatData m_jointAxisTop[6]; btVector3FloatData m_jointAxisBottom[6]; - btVector3FloatData m_linkInertia; // inertia of the base (in local frame; diagonal) - btVector3FloatData m_absFrameTotVelocityTop; - btVector3FloatData m_absFrameTotVelocityBottom; - btVector3FloatData m_absFrameLocVelocityTop; - btVector3FloatData m_absFrameLocVelocityBottom; - + btVector3FloatData m_linkInertia; // inertia of the base (in local frame; diagonal) int m_dofCount; float m_linkMass; int m_parentIndex; @@ -797,38 +784,29 @@ struct btMultiBodyLinkFloatData ///do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64 struct btMultiBodyDoubleData { - btVector3DoubleData m_baseWorldPosition; - btQuaternionDoubleData m_baseWorldOrientation; - btVector3DoubleData m_baseLinearVelocity; - btVector3DoubleData m_baseAngularVelocity; + btTransformDoubleData m_baseWorldTransform; btVector3DoubleData m_baseInertia; // inertia of the base (in local frame; diagonal) double m_baseMass; - int m_numLinks; - char m_padding[4]; char *m_baseName; btMultiBodyLinkDoubleData *m_links; btCollisionObjectDoubleData *m_baseCollider; - - + char *m_paddingPtr; + int m_numLinks; + char m_padding[4]; }; ///do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64 struct btMultiBodyFloatData { - btVector3FloatData m_baseWorldPosition; - btQuaternionFloatData m_baseWorldOrientation; - btVector3FloatData m_baseLinearVelocity; - btVector3FloatData m_baseAngularVelocity; - - btVector3FloatData m_baseInertia; // inertia of the base (in local frame; diagonal) - float m_baseMass; - int m_numLinks; - char *m_baseName; btMultiBodyLinkFloatData *m_links; btCollisionObjectFloatData *m_baseCollider; - + btTransformFloatData m_baseWorldTransform; + btVector3FloatData m_baseInertia; // inertia of the base (in local frame; diagonal) + + float m_baseMass; + int m_numLinks; }; diff --git a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraint.cpp b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraint.cpp index 9f61874b8372..d52852dd8e9a 100644 --- a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraint.cpp +++ b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraint.cpp @@ -253,7 +253,7 @@ btScalar btMultiBodyConstraint::fillMultiBodyConstraint( btMultiBodySolverConstr { vec = ( solverConstraint.m_angularComponentA).cross(rel_pos1); if (angConstraint) { - denom0 = constraintNormalAng.dot(solverConstraint.m_angularComponentA); + denom0 = rb0->getInvMass() + constraintNormalAng.dot(vec); } else { denom0 = rb0->getInvMass() + constraintNormalLin.dot(vec); @@ -277,7 +277,7 @@ btScalar btMultiBodyConstraint::fillMultiBodyConstraint( btMultiBodySolverConstr { vec = ( -solverConstraint.m_angularComponentB).cross(rel_pos2); if (angConstraint) { - denom1 = constraintNormalAng.dot(-solverConstraint.m_angularComponentB); + denom1 = rb1->getInvMass() + constraintNormalAng.dot(vec); } else { denom1 = rb1->getInvMass() + constraintNormalLin.dot(vec); @@ -315,8 +315,7 @@ btScalar btMultiBodyConstraint::fillMultiBodyConstraint( btMultiBodySolverConstr } else if(rb0) { - rel_vel += rb0->getLinearVelocity().dot(solverConstraint.m_contactNormal1); - rel_vel += rb0->getAngularVelocity().dot(solverConstraint.m_relpos1CrossNormal); + rel_vel += rb0->getVelocityInLocalPoint(rel_pos1).dot(solverConstraint.m_contactNormal1); } if (multiBodyB) { @@ -328,8 +327,7 @@ btScalar btMultiBodyConstraint::fillMultiBodyConstraint( btMultiBodySolverConstr } else if(rb1) { - rel_vel += rb1->getLinearVelocity().dot(solverConstraint.m_contactNormal2); - rel_vel += rb1->getAngularVelocity().dot(solverConstraint.m_relpos2CrossNormal); + rel_vel += rb1->getVelocityInLocalPoint(rel_pos2).dot(solverConstraint.m_contactNormal2); } solverConstraint.m_friction = 0.f;//cp.m_combinedFriction; diff --git a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraint.h b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraint.h index a2ae57127332..83521b9501b5 100644 --- a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraint.h +++ b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraint.h @@ -119,14 +119,6 @@ ATTRIBUTE_ALIGNED16(class) btMultiBodyConstraint return m_bodyB; } - int getLinkA() const - { - return m_linkA; - } - int getLinkB() const - { - return m_linkB; - } void internalSetAppliedImpulse(int dof, btScalar appliedImpulse) { btAssert(dof>=0); diff --git a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp index 6fd34d311ca2..1e2d07409609 100644 --- a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp +++ b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp @@ -39,7 +39,7 @@ btScalar btMultiBodyConstraintSolver::solveSingleIteration(int iteration, btColl btMultiBodySolverConstraint& constraint = m_multiBodyNonContactConstraints[index]; btScalar residual = resolveSingleConstraintRowGeneric(constraint); - leastSquaredResidual = btMax(leastSquaredResidual,residual*residual); + leastSquaredResidual += residual*residual; if(constraint.m_multiBodyA) constraint.m_multiBodyA->setPosUpdated(false); @@ -60,101 +60,36 @@ btScalar btMultiBodyConstraintSolver::solveSingleIteration(int iteration, btColl residual = resolveSingleConstraintRowGeneric(constraint); } - leastSquaredResidual = btMax(leastSquaredResidual,residual*residual); + leastSquaredResidual += residual*residual; if(constraint.m_multiBodyA) constraint.m_multiBodyA->setPosUpdated(false); if(constraint.m_multiBodyB) constraint.m_multiBodyB->setPosUpdated(false); } - + //solve featherstone frictional contact - if (infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS && ((infoGlobal.m_solverMode&SOLVER_DISABLE_IMPLICIT_CONE_FRICTION) == 0)) - { - for (int j1 = 0; j1m_multiBodyTorsionalFrictionContactConstraints.size(); j1++) - { - if (iteration < infoGlobal.m_numIterations) - { - int index = j1;//iteration&1? j1 : m_multiBodyTorsionalFrictionContactConstraints.size()-1-j1; - - btMultiBodySolverConstraint& frictionConstraint = m_multiBodyTorsionalFrictionContactConstraints[index]; - btScalar totalImpulse = m_multiBodyNormalContactConstraints[frictionConstraint.m_frictionIndex].m_appliedImpulse; - //adjust friction limits here - if (totalImpulse>btScalar(0)) - { - frictionConstraint.m_lowerLimit = -(frictionConstraint.m_friction*totalImpulse); - frictionConstraint.m_upperLimit = frictionConstraint.m_friction*totalImpulse; - btScalar residual = resolveSingleConstraintRowGeneric(frictionConstraint); - leastSquaredResidual = btMax(leastSquaredResidual , residual*residual); - - if (frictionConstraint.m_multiBodyA) - frictionConstraint.m_multiBodyA->setPosUpdated(false); - if (frictionConstraint.m_multiBodyB) - frictionConstraint.m_multiBodyB->setPosUpdated(false); - } - } - } - - for (int j1 = 0; j1 < this->m_multiBodyFrictionContactConstraints.size(); j1++) - { - if (iteration < infoGlobal.m_numIterations) - { - int index = j1;//iteration&1? j1 : m_multiBodyFrictionContactConstraints.size()-1-j1; - btMultiBodySolverConstraint& frictionConstraint = m_multiBodyFrictionContactConstraints[index]; - - btScalar totalImpulse = m_multiBodyNormalContactConstraints[frictionConstraint.m_frictionIndex].m_appliedImpulse; - j1++; - int index2 = j1;//iteration&1? j1 : m_multiBodyFrictionContactConstraints.size()-1-j1; - btMultiBodySolverConstraint& frictionConstraintB = m_multiBodyFrictionContactConstraints[index2]; - btAssert(frictionConstraint.m_frictionIndex == frictionConstraintB.m_frictionIndex); - - if (frictionConstraint.m_frictionIndex == frictionConstraintB.m_frictionIndex) - { - frictionConstraint.m_lowerLimit = -(frictionConstraint.m_friction*totalImpulse); - frictionConstraint.m_upperLimit = frictionConstraint.m_friction*totalImpulse; - frictionConstraintB.m_lowerLimit = -(frictionConstraintB.m_friction*totalImpulse); - frictionConstraintB.m_upperLimit = frictionConstraintB.m_friction*totalImpulse; - btScalar residual = resolveConeFrictionConstraintRows(frictionConstraint, frictionConstraintB); - leastSquaredResidual = btMax(leastSquaredResidual, residual*residual); - - if (frictionConstraintB.m_multiBodyA) - frictionConstraintB.m_multiBodyA->setPosUpdated(false); - if (frictionConstraintB.m_multiBodyB) - frictionConstraintB.m_multiBodyB->setPosUpdated(false); - - if (frictionConstraint.m_multiBodyA) - frictionConstraint.m_multiBodyA->setPosUpdated(false); - if (frictionConstraint.m_multiBodyB) - frictionConstraint.m_multiBodyB->setPosUpdated(false); - } - } - } - - } - else + for (int j1=0;j1m_multiBodyFrictionContactConstraints.size();j1++) { - for (int j1 = 0; j1m_multiBodyFrictionContactConstraints.size(); j1++) + if (iteration < infoGlobal.m_numIterations) { - if (iteration < infoGlobal.m_numIterations) - { - int index = j1;//iteration&1? j1 : m_multiBodyFrictionContactConstraints.size()-1-j1; + int index = j1;//iteration&1? j1 : m_multiBodyFrictionContactConstraints.size()-1-j1; - btMultiBodySolverConstraint& frictionConstraint = m_multiBodyFrictionContactConstraints[index]; - btScalar totalImpulse = m_multiBodyNormalContactConstraints[frictionConstraint.m_frictionIndex].m_appliedImpulse; - //adjust friction limits here - if (totalImpulse>btScalar(0)) - { - frictionConstraint.m_lowerLimit = -(frictionConstraint.m_friction*totalImpulse); - frictionConstraint.m_upperLimit = frictionConstraint.m_friction*totalImpulse; - btScalar residual = resolveSingleConstraintRowGeneric(frictionConstraint); - leastSquaredResidual = btMax(leastSquaredResidual, residual*residual); - - if (frictionConstraint.m_multiBodyA) - frictionConstraint.m_multiBodyA->setPosUpdated(false); - if (frictionConstraint.m_multiBodyB) - frictionConstraint.m_multiBodyB->setPosUpdated(false); - } + btMultiBodySolverConstraint& frictionConstraint = m_multiBodyFrictionContactConstraints[index]; + btScalar totalImpulse = m_multiBodyNormalContactConstraints[frictionConstraint.m_frictionIndex].m_appliedImpulse; + //adjust friction limits here + if (totalImpulse>btScalar(0)) + { + frictionConstraint.m_lowerLimit = -(frictionConstraint.m_friction*totalImpulse); + frictionConstraint.m_upperLimit = frictionConstraint.m_friction*totalImpulse; + btScalar residual = resolveSingleConstraintRowGeneric(frictionConstraint); + leastSquaredResidual += residual*residual; + + if(frictionConstraint.m_multiBodyA) + frictionConstraint.m_multiBodyA->setPosUpdated(false); + if(frictionConstraint.m_multiBodyB) + frictionConstraint.m_multiBodyB->setPosUpdated(false); } } } @@ -166,8 +101,6 @@ btScalar btMultiBodyConstraintSolver::solveGroupCacheFriendlySetup(btCollisionOb m_multiBodyNonContactConstraints.resize(0); m_multiBodyNormalContactConstraints.resize(0); m_multiBodyFrictionContactConstraints.resize(0); - m_multiBodyTorsionalFrictionContactConstraints.resize(0); - m_data.m_jacobians.resize(0); m_data.m_deltaVelocitiesUnitImpulse.resize(0); m_data.m_deltaVelocities.resize(0); @@ -195,267 +128,82 @@ void btMultiBodyConstraintSolver::applyDeltaVee(btScalar* delta_vee, btScalar im btScalar btMultiBodyConstraintSolver::resolveSingleConstraintRowGeneric(const btMultiBodySolverConstraint& c) { - btScalar deltaImpulse = c.m_rhs - btScalar(c.m_appliedImpulse)*c.m_cfm; - btScalar deltaVelADotn = 0; - btScalar deltaVelBDotn = 0; + btScalar deltaImpulse = c.m_rhs-btScalar(c.m_appliedImpulse)*c.m_cfm; + btScalar deltaVelADotn=0; + btScalar deltaVelBDotn=0; btSolverBody* bodyA = 0; btSolverBody* bodyB = 0; - int ndofA = 0; - int ndofB = 0; + int ndofA=0; + int ndofB=0; if (c.m_multiBodyA) { - ndofA = c.m_multiBodyA->getNumDofs() + 6; - for (int i = 0; i < ndofA; ++i) - deltaVelADotn += m_data.m_jacobians[c.m_jacAindex + i] * m_data.m_deltaVelocities[c.m_deltaVelAindex + i]; - } - else if (c.m_solverBodyIdA >= 0) + ndofA = c.m_multiBodyA->getNumDofs() + 6; + for (int i = 0; i < ndofA; ++i) + deltaVelADotn += m_data.m_jacobians[c.m_jacAindex+i] * m_data.m_deltaVelocities[c.m_deltaVelAindex+i]; + } else if(c.m_solverBodyIdA >= 0) { bodyA = &m_tmpSolverBodyPool[c.m_solverBodyIdA]; - deltaVelADotn += c.m_contactNormal1.dot(bodyA->internalGetDeltaLinearVelocity()) + c.m_relpos1CrossNormal.dot(bodyA->internalGetDeltaAngularVelocity()); + deltaVelADotn += c.m_contactNormal1.dot(bodyA->internalGetDeltaLinearVelocity()) + c.m_relpos1CrossNormal.dot(bodyA->internalGetDeltaAngularVelocity()); } if (c.m_multiBodyB) { - ndofB = c.m_multiBodyB->getNumDofs() + 6; - for (int i = 0; i < ndofB; ++i) - deltaVelBDotn += m_data.m_jacobians[c.m_jacBindex + i] * m_data.m_deltaVelocities[c.m_deltaVelBindex + i]; - } - else if (c.m_solverBodyIdB >= 0) + ndofB = c.m_multiBodyB->getNumDofs() + 6; + for (int i = 0; i < ndofB; ++i) + deltaVelBDotn += m_data.m_jacobians[c.m_jacBindex+i] * m_data.m_deltaVelocities[c.m_deltaVelBindex+i]; + } else if(c.m_solverBodyIdB >= 0) { bodyB = &m_tmpSolverBodyPool[c.m_solverBodyIdB]; - deltaVelBDotn += c.m_contactNormal2.dot(bodyB->internalGetDeltaLinearVelocity()) + c.m_relpos2CrossNormal.dot(bodyB->internalGetDeltaAngularVelocity()); + deltaVelBDotn += c.m_contactNormal2.dot(bodyB->internalGetDeltaLinearVelocity()) + c.m_relpos2CrossNormal.dot(bodyB->internalGetDeltaAngularVelocity()); } - - deltaImpulse -= deltaVelADotn*c.m_jacDiagABInv;//m_jacDiagABInv = 1./denom - deltaImpulse -= deltaVelBDotn*c.m_jacDiagABInv; + + deltaImpulse -= deltaVelADotn*c.m_jacDiagABInv;//m_jacDiagABInv = 1./denom + deltaImpulse -= deltaVelBDotn*c.m_jacDiagABInv; const btScalar sum = btScalar(c.m_appliedImpulse) + deltaImpulse; - + if (sum < c.m_lowerLimit) { - deltaImpulse = c.m_lowerLimit - c.m_appliedImpulse; + deltaImpulse = c.m_lowerLimit-c.m_appliedImpulse; c.m_appliedImpulse = c.m_lowerLimit; } - else if (sum > c.m_upperLimit) + else if (sum > c.m_upperLimit) { - deltaImpulse = c.m_upperLimit - c.m_appliedImpulse; + deltaImpulse = c.m_upperLimit-c.m_appliedImpulse; c.m_appliedImpulse = c.m_upperLimit; } else { c.m_appliedImpulse = sum; } - + if (c.m_multiBodyA) { - applyDeltaVee(&m_data.m_deltaVelocitiesUnitImpulse[c.m_jacAindex], deltaImpulse, c.m_deltaVelAindex, ndofA); + applyDeltaVee(&m_data.m_deltaVelocitiesUnitImpulse[c.m_jacAindex],deltaImpulse,c.m_deltaVelAindex,ndofA); #ifdef DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS //note: update of the actual velocities (below) in the multibody does not have to happen now since m_deltaVelocities can be applied after all iterations //it would make the multibody solver more like the regular one with m_deltaVelocities being equivalent to btSolverBody::m_deltaLinearVelocity/m_deltaAngularVelocity - c.m_multiBodyA->applyDeltaVeeMultiDof2(&m_data.m_deltaVelocitiesUnitImpulse[c.m_jacAindex], deltaImpulse); + c.m_multiBodyA->applyDeltaVeeMultiDof2(&m_data.m_deltaVelocitiesUnitImpulse[c.m_jacAindex],deltaImpulse); #endif //DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS - } - else if (c.m_solverBodyIdA >= 0) + } else if(c.m_solverBodyIdA >= 0) { - bodyA->internalApplyImpulse(c.m_contactNormal1*bodyA->internalGetInvMass(), c.m_angularComponentA, deltaImpulse); + bodyA->internalApplyImpulse(c.m_contactNormal1*bodyA->internalGetInvMass(),c.m_angularComponentA,deltaImpulse); } if (c.m_multiBodyB) { - applyDeltaVee(&m_data.m_deltaVelocitiesUnitImpulse[c.m_jacBindex], deltaImpulse, c.m_deltaVelBindex, ndofB); -#ifdef DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS - //note: update of the actual velocities (below) in the multibody does not have to happen now since m_deltaVelocities can be applied after all iterations - //it would make the multibody solver more like the regular one with m_deltaVelocities being equivalent to btSolverBody::m_deltaLinearVelocity/m_deltaAngularVelocity - c.m_multiBodyB->applyDeltaVeeMultiDof2(&m_data.m_deltaVelocitiesUnitImpulse[c.m_jacBindex], deltaImpulse); -#endif //DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS - } - else if (c.m_solverBodyIdB >= 0) - { - bodyB->internalApplyImpulse(c.m_contactNormal2*bodyB->internalGetInvMass(), c.m_angularComponentB, deltaImpulse); - } - btScalar deltaVel =deltaImpulse/c.m_jacDiagABInv; - return deltaVel; -} - - -btScalar btMultiBodyConstraintSolver::resolveConeFrictionConstraintRows(const btMultiBodySolverConstraint& cA1,const btMultiBodySolverConstraint& cB) -{ - int ndofA=0; - int ndofB=0; - btSolverBody* bodyA = 0; - btSolverBody* bodyB = 0; - btScalar deltaImpulseB = 0.f; - btScalar sumB = 0.f; - { - deltaImpulseB = cB.m_rhs-btScalar(cB.m_appliedImpulse)*cB.m_cfm; - btScalar deltaVelADotn=0; - btScalar deltaVelBDotn=0; - if (cB.m_multiBodyA) - { - ndofA = cB.m_multiBodyA->getNumDofs() + 6; - for (int i = 0; i < ndofA; ++i) - deltaVelADotn += m_data.m_jacobians[cB.m_jacAindex+i] * m_data.m_deltaVelocities[cB.m_deltaVelAindex+i]; - } else if(cB.m_solverBodyIdA >= 0) - { - bodyA = &m_tmpSolverBodyPool[cB.m_solverBodyIdA]; - deltaVelADotn += cB.m_contactNormal1.dot(bodyA->internalGetDeltaLinearVelocity()) + cB.m_relpos1CrossNormal.dot(bodyA->internalGetDeltaAngularVelocity()); - } - - if (cB.m_multiBodyB) - { - ndofB = cB.m_multiBodyB->getNumDofs() + 6; - for (int i = 0; i < ndofB; ++i) - deltaVelBDotn += m_data.m_jacobians[cB.m_jacBindex+i] * m_data.m_deltaVelocities[cB.m_deltaVelBindex+i]; - } else if(cB.m_solverBodyIdB >= 0) - { - bodyB = &m_tmpSolverBodyPool[cB.m_solverBodyIdB]; - deltaVelBDotn += cB.m_contactNormal2.dot(bodyB->internalGetDeltaLinearVelocity()) + cB.m_relpos2CrossNormal.dot(bodyB->internalGetDeltaAngularVelocity()); - } - - - deltaImpulseB -= deltaVelADotn*cB.m_jacDiagABInv;//m_jacDiagABInv = 1./denom - deltaImpulseB -= deltaVelBDotn*cB.m_jacDiagABInv; - sumB = btScalar(cB.m_appliedImpulse) + deltaImpulseB; - } - - btScalar deltaImpulseA = 0.f; - btScalar sumA = 0.f; - const btMultiBodySolverConstraint& cA = cA1; - { - { - deltaImpulseA = cA.m_rhs-btScalar(cA.m_appliedImpulse)*cA.m_cfm; - btScalar deltaVelADotn=0; - btScalar deltaVelBDotn=0; - if (cA.m_multiBodyA) - { - ndofA = cA.m_multiBodyA->getNumDofs() + 6; - for (int i = 0; i < ndofA; ++i) - deltaVelADotn += m_data.m_jacobians[cA.m_jacAindex+i] * m_data.m_deltaVelocities[cA.m_deltaVelAindex+i]; - } else if(cA.m_solverBodyIdA >= 0) - { - bodyA = &m_tmpSolverBodyPool[cA.m_solverBodyIdA]; - deltaVelADotn += cA.m_contactNormal1.dot(bodyA->internalGetDeltaLinearVelocity()) + cA.m_relpos1CrossNormal.dot(bodyA->internalGetDeltaAngularVelocity()); - } - - if (cA.m_multiBodyB) - { - ndofB = cA.m_multiBodyB->getNumDofs() + 6; - for (int i = 0; i < ndofB; ++i) - deltaVelBDotn += m_data.m_jacobians[cA.m_jacBindex+i] * m_data.m_deltaVelocities[cA.m_deltaVelBindex+i]; - } else if(cA.m_solverBodyIdB >= 0) - { - bodyB = &m_tmpSolverBodyPool[cA.m_solverBodyIdB]; - deltaVelBDotn += cA.m_contactNormal2.dot(bodyB->internalGetDeltaLinearVelocity()) + cA.m_relpos2CrossNormal.dot(bodyB->internalGetDeltaAngularVelocity()); - } - - - deltaImpulseA -= deltaVelADotn*cA.m_jacDiagABInv;//m_jacDiagABInv = 1./denom - deltaImpulseA -= deltaVelBDotn*cA.m_jacDiagABInv; - sumA = btScalar(cA.m_appliedImpulse) + deltaImpulseA; - } - } - - if (sumA*sumA+sumB*sumB>=cA.m_lowerLimit*cB.m_lowerLimit) - { - btScalar angle = btAtan2(sumA,sumB); - btScalar sumAclipped = btFabs(cA.m_lowerLimit*btSin(angle)); - btScalar sumBclipped = btFabs(cB.m_lowerLimit*btCos(angle)); - - - if (sumA < -sumAclipped) - { - deltaImpulseA = -sumAclipped - cA.m_appliedImpulse; - cA.m_appliedImpulse = -sumAclipped; - } - else if (sumA > sumAclipped) - { - deltaImpulseA = sumAclipped - cA.m_appliedImpulse; - cA.m_appliedImpulse = sumAclipped; - } - else - { - cA.m_appliedImpulse = sumA; - } - - if (sumB < -sumBclipped) - { - deltaImpulseB = -sumBclipped - cB.m_appliedImpulse; - cB.m_appliedImpulse = -sumBclipped; - } - else if (sumB > sumBclipped) - { - deltaImpulseB = sumBclipped - cB.m_appliedImpulse; - cB.m_appliedImpulse = sumBclipped; - } - else - { - cB.m_appliedImpulse = sumB; - } - //deltaImpulseA = sumAclipped-cA.m_appliedImpulse; - //cA.m_appliedImpulse = sumAclipped; - //deltaImpulseB = sumBclipped-cB.m_appliedImpulse; - //cB.m_appliedImpulse = sumBclipped; - } - else - { - cA.m_appliedImpulse = sumA; - cB.m_appliedImpulse = sumB; - } - - if (cA.m_multiBodyA) - { - applyDeltaVee(&m_data.m_deltaVelocitiesUnitImpulse[cA.m_jacAindex],deltaImpulseA,cA.m_deltaVelAindex,ndofA); + applyDeltaVee(&m_data.m_deltaVelocitiesUnitImpulse[c.m_jacBindex],deltaImpulse,c.m_deltaVelBindex,ndofB); #ifdef DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS //note: update of the actual velocities (below) in the multibody does not have to happen now since m_deltaVelocities can be applied after all iterations //it would make the multibody solver more like the regular one with m_deltaVelocities being equivalent to btSolverBody::m_deltaLinearVelocity/m_deltaAngularVelocity - cA.m_multiBodyA->applyDeltaVeeMultiDof2(&m_data.m_deltaVelocitiesUnitImpulse[cA.m_jacAindex],deltaImpulseA); + c.m_multiBodyB->applyDeltaVeeMultiDof2(&m_data.m_deltaVelocitiesUnitImpulse[c.m_jacBindex],deltaImpulse); #endif //DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS - } else if(cA.m_solverBodyIdA >= 0) + } else if(c.m_solverBodyIdB >= 0) { - bodyA->internalApplyImpulse(cA.m_contactNormal1*bodyA->internalGetInvMass(),cA.m_angularComponentA,deltaImpulseA); - + bodyB->internalApplyImpulse(c.m_contactNormal2*bodyB->internalGetInvMass(),c.m_angularComponentB,deltaImpulse); } - if (cA.m_multiBodyB) - { - applyDeltaVee(&m_data.m_deltaVelocitiesUnitImpulse[cA.m_jacBindex],deltaImpulseA,cA.m_deltaVelBindex,ndofB); -#ifdef DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS - //note: update of the actual velocities (below) in the multibody does not have to happen now since m_deltaVelocities can be applied after all iterations - //it would make the multibody solver more like the regular one with m_deltaVelocities being equivalent to btSolverBody::m_deltaLinearVelocity/m_deltaAngularVelocity - cA.m_multiBodyB->applyDeltaVeeMultiDof2(&m_data.m_deltaVelocitiesUnitImpulse[cA.m_jacBindex],deltaImpulseA); -#endif //DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS - } else if(cA.m_solverBodyIdB >= 0) - { - bodyB->internalApplyImpulse(cA.m_contactNormal2*bodyB->internalGetInvMass(),cA.m_angularComponentB,deltaImpulseA); - } - - if (cB.m_multiBodyA) - { - applyDeltaVee(&m_data.m_deltaVelocitiesUnitImpulse[cB.m_jacAindex],deltaImpulseB,cB.m_deltaVelAindex,ndofA); -#ifdef DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS - //note: update of the actual velocities (below) in the multibody does not have to happen now since m_deltaVelocities can be applied after all iterations - //it would make the multibody solver more like the regular one with m_deltaVelocities being equivalent to btSolverBody::m_deltaLinearVelocity/m_deltaAngularVelocity - cB.m_multiBodyA->applyDeltaVeeMultiDof2(&m_data.m_deltaVelocitiesUnitImpulse[cB.m_jacAindex],deltaImpulseB); -#endif //DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS - } else if(cB.m_solverBodyIdA >= 0) - { - bodyA->internalApplyImpulse(cB.m_contactNormal1*bodyA->internalGetInvMass(),cB.m_angularComponentA,deltaImpulseB); - } - if (cB.m_multiBodyB) - { - applyDeltaVee(&m_data.m_deltaVelocitiesUnitImpulse[cB.m_jacBindex],deltaImpulseB,cB.m_deltaVelBindex,ndofB); -#ifdef DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS - //note: update of the actual velocities (below) in the multibody does not have to happen now since m_deltaVelocities can be applied after all iterations - //it would make the multibody solver more like the regular one with m_deltaVelocities being equivalent to btSolverBody::m_deltaLinearVelocity/m_deltaAngularVelocity - cB.m_multiBodyB->applyDeltaVeeMultiDof2(&m_data.m_deltaVelocitiesUnitImpulse[cB.m_jacBindex],deltaImpulseB); -#endif //DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS - } else if(cB.m_solverBodyIdB >= 0) - { - bodyB->internalApplyImpulse(cB.m_contactNormal2*bodyB->internalGetInvMass(),cB.m_angularComponentB,deltaImpulseB); - } - - btScalar deltaVel =deltaImpulseA/cA.m_jacDiagABInv+deltaImpulseB/cB.m_jacDiagABInv; - return deltaVel; + return deltaImpulse; } @@ -1160,10 +908,7 @@ btMultiBodySolverConstraint& btMultiBodyConstraintSolver::addMultiBodyTorsionalF btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity, btScalar cfmSlip) { BT_PROFILE("addMultiBodyRollingFrictionConstraint"); - - bool useTorsionalAndConeFriction = (infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS && ((infoGlobal.m_solverMode&SOLVER_DISABLE_IMPLICIT_CONE_FRICTION) == 0)); - - btMultiBodySolverConstraint& solverConstraint = useTorsionalAndConeFriction? m_multiBodyTorsionalFrictionContactConstraints.expandNonInitializing() : m_multiBodyFrictionContactConstraints.expandNonInitializing(); + btMultiBodySolverConstraint& solverConstraint = m_multiBodyFrictionContactConstraints.expandNonInitializing(); solverConstraint.m_orgConstraint = 0; solverConstraint.m_orgDofIndex = -1; @@ -1489,12 +1234,27 @@ void btMultiBodyConstraintSolver::writeBackSolverBodyToMultiBody(btMultiBodySolv if (c.m_multiBodyA) { - c.m_multiBodyA->applyDeltaVeeMultiDof(&m_data.m_deltaVelocitiesUnitImpulse[c.m_jacAindex],c.m_appliedImpulse); + + if(c.m_multiBodyA->isMultiDof()) + { + c.m_multiBodyA->applyDeltaVeeMultiDof(&m_data.m_deltaVelocitiesUnitImpulse[c.m_jacAindex],c.m_appliedImpulse); + } + else + { + c.m_multiBodyA->applyDeltaVee(&m_data.m_deltaVelocitiesUnitImpulse[c.m_jacAindex],c.m_appliedImpulse); + } } if (c.m_multiBodyB) { - c.m_multiBodyB->applyDeltaVeeMultiDof(&m_data.m_deltaVelocitiesUnitImpulse[c.m_jacBindex],c.m_appliedImpulse); + if(c.m_multiBodyB->isMultiDof()) + { + c.m_multiBodyB->applyDeltaVeeMultiDof(&m_data.m_deltaVelocitiesUnitImpulse[c.m_jacBindex],c.m_appliedImpulse); + } + else + { + c.m_multiBodyB->applyDeltaVee(&m_data.m_deltaVelocitiesUnitImpulse[c.m_jacBindex],c.m_appliedImpulse); + } } #endif diff --git a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h index 29f484e1d8df..489347d874fa 100644 --- a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h +++ b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h @@ -36,7 +36,6 @@ ATTRIBUTE_ALIGNED16(class) btMultiBodyConstraintSolver : public btSequentialImpu btMultiBodyConstraintArray m_multiBodyNormalContactConstraints; btMultiBodyConstraintArray m_multiBodyFrictionContactConstraints; - btMultiBodyConstraintArray m_multiBodyTorsionalFrictionContactConstraints; btMultiBodyJacobianData m_data; @@ -46,9 +45,6 @@ ATTRIBUTE_ALIGNED16(class) btMultiBodyConstraintSolver : public btSequentialImpu btScalar resolveSingleConstraintRowGeneric(const btMultiBodySolverConstraint& c); - //solve 2 friction directions and clamp against the implicit friction cone - btScalar resolveConeFrictionConstraintRows(const btMultiBodySolverConstraint& cA1, const btMultiBodySolverConstraint& cB); - void convertContacts(btPersistentManifold** manifoldPtr,int numManifolds, const btContactSolverInfo& infoGlobal); diff --git a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp index a2be068ed5f3..9eacc2264703 100644 --- a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp +++ b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp @@ -411,8 +411,6 @@ void btMultiBodyDynamicsWorld::solveConstraints(btContactSolverInfo& solverInfo) BT_PROFILE("solveConstraints"); - clearMultiBodyConstraintForces(); - m_sortedConstraints.resize( m_constraints.size()); int i; for (i=0;iprocessConstraints(); @@ -826,24 +824,21 @@ void btMultiBodyDynamicsWorld::debugDrawWorld() { btMultiBody* bod = m_multiBodies[b]; bod->forwardKinematics(m_scratch_world_to_local1,m_scratch_local_origin1); - - if (mode & btIDebugDraw::DBG_DrawFrames) - { - getDebugDrawer()->drawTransform(bod->getBaseWorldTransform(), 0.1); - } + + getDebugDrawer()->drawTransform(bod->getBaseWorldTransform(), 0.1); + for (int m = 0; mgetNumLinks(); m++) { const btTransform& tr = bod->getLink(m).m_cachedWorldTransform; - if (mode & btIDebugDraw::DBG_DrawFrames) - { - getDebugDrawer()->drawTransform(tr, 0.1); - } + + getDebugDrawer()->drawTransform(tr, 0.1); + //draw the joint axis if (bod->getLink(m).m_jointType==btMultibodyLink::eRevolute) { - btVector3 vec = quatRotate(tr.getRotation(),bod->getLink(m).m_axes[0].m_topVec)*0.1; + btVector3 vec = quatRotate(tr.getRotation(),bod->getLink(m).m_axes[0].m_topVec); btVector4 color(0,0,0,1);//1,1,1); btVector3 from = vec+tr.getOrigin()-quatRotate(tr.getRotation(),bod->getLink(m).m_dVector); @@ -852,7 +847,7 @@ void btMultiBodyDynamicsWorld::debugDrawWorld() } if (bod->getLink(m).m_jointType==btMultibodyLink::eFixed) { - btVector3 vec = quatRotate(tr.getRotation(),bod->getLink(m).m_axes[0].m_bottomVec)*0.1; + btVector3 vec = quatRotate(tr.getRotation(),bod->getLink(m).m_axes[0].m_bottomVec); btVector4 color(0,0,0,1);//1,1,1); btVector3 from = vec+tr.getOrigin()-quatRotate(tr.getRotation(),bod->getLink(m).m_dVector); @@ -861,7 +856,7 @@ void btMultiBodyDynamicsWorld::debugDrawWorld() } if (bod->getLink(m).m_jointType==btMultibodyLink::ePrismatic) { - btVector3 vec = quatRotate(tr.getRotation(),bod->getLink(m).m_axes[0].m_bottomVec)*0.1; + btVector3 vec = quatRotate(tr.getRotation(),bod->getLink(m).m_axes[0].m_bottomVec); btVector4 color(0,0,0,1);//1,1,1); btVector3 from = vec+tr.getOrigin()-quatRotate(tr.getRotation(),bod->getLink(m).m_dVector); @@ -975,8 +970,6 @@ void btMultiBodyDynamicsWorld::serialize(btSerializer* serializer) serializeCollisionObjects(serializer); - serializeContactManifolds(serializer); - serializer->finishSerialization(); } @@ -995,17 +988,4 @@ void btMultiBodyDynamicsWorld::serializeMultiBodies(btSerializer* serializer) } } - //serialize all multibody links (collision objects) - for (i=0;igetInternalType() == btCollisionObject::CO_FEATHERSTONE_LINK) - { - int len = colObj->calculateSerializeBufferSize(); - btChunk* chunk = serializer->allocate(len,1); - const char* structType = colObj->serialize(chunk->m_oldPtr, serializer); - serializer->finalizeChunk(chunk,structType,BT_MB_LINKCOLLIDER_CODE,colObj); - } - } - } \ No newline at end of file diff --git a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyFixedConstraint.cpp b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyFixedConstraint.cpp index 339b3800c1ae..0f0d9f67b8f8 100644 --- a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyFixedConstraint.cpp +++ b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyFixedConstraint.cpp @@ -156,7 +156,7 @@ void btMultiBodyFixedConstraint::createConstraintRows(btMultiBodyConstraintArray btVector3 constraintNormalAng(0,0,0); btScalar posError = 0.0; if (i < 3) { - constraintNormalLin[i] = 1; + constraintNormalLin[i] = -1; posError = (pivotAworld-pivotBworld).dot(constraintNormalLin); fillMultiBodyConstraint(constraintRow, data, 0, 0, constraintNormalAng, constraintNormalLin, pivotAworld, pivotBworld, diff --git a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyGearConstraint.cpp b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyGearConstraint.cpp index b54a228ba62a..5fdb7007d81d 100644 --- a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyGearConstraint.cpp +++ b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyGearConstraint.cpp @@ -134,10 +134,6 @@ void btMultiBodyGearConstraint::createConstraintRows(btMultiBodyConstraintArray& if (m_erp!=0) { btScalar currentPositionA = m_bodyA->getJointPosMultiDof(m_linkA)[dof]; - if (m_gearAuxLink >= 0) - { - currentPositionA -= m_bodyA->getJointPosMultiDof(m_gearAuxLink)[dof]; - } btScalar currentPositionB = m_gearRatio*m_bodyA->getJointPosMultiDof(m_linkB)[dof]; btScalar diff = currentPositionB+currentPositionA; btScalar desiredPositionDiff = this->m_relativePositionTarget; diff --git a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyLink.h b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyLink.h index 13e906cd65db..8129ae9013d3 100644 --- a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyLink.h +++ b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyLink.h @@ -182,8 +182,6 @@ btVector3 m_appliedConstraintForce; // In WORLD frame m_cachedRVector.setValue(0, 0, 0); m_appliedForce.setValue( 0, 0, 0); m_appliedTorque.setValue(0, 0, 0); - m_appliedConstraintForce.setValue(0,0,0); - m_appliedConstraintTorque.setValue(0,0,0); // m_jointPos[0] = m_jointPos[1] = m_jointPos[2] = m_jointPos[4] = m_jointPos[5] = m_jointPos[6] = 0.f; m_jointPos[3] = 1.f; //"quat.w" diff --git a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyLinkCollider.h b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyLinkCollider.h index 7092e62b5ae3..671e15d314d4 100644 --- a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyLinkCollider.h +++ b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyLinkCollider.h @@ -19,16 +19,6 @@ subject to the following restrictions: #include "BulletCollision/CollisionDispatch/btCollisionObject.h" #include "btMultiBody.h" -#include "LinearMath/btSerializer.h" - -#ifdef BT_USE_DOUBLE_PRECISION -#define btMultiBodyLinkColliderData btMultiBodyLinkColliderDoubleData -#define btMultiBodyLinkColliderDataName "btMultiBodyLinkColliderDoubleData" -#else -#define btMultiBodyLinkColliderData btMultiBodyLinkColliderFloatData -#define btMultiBodyLinkColliderDataName "btMultiBodyLinkColliderFloatData" -#endif - class btMultiBodyLinkCollider : public btCollisionObject { @@ -129,49 +119,7 @@ class btMultiBodyLinkCollider : public btCollisionObject } return true; } - - virtual int calculateSerializeBufferSize() const; - - ///fills the dataBuffer and returns the struct name (and 0 on failure) - virtual const char* serialize(void* dataBuffer, class btSerializer* serializer) const; - -}; - - -struct btMultiBodyLinkColliderFloatData -{ - btCollisionObjectFloatData m_colObjData; - btMultiBodyFloatData *m_multiBody; - int m_link; - char m_padding[4]; }; -struct btMultiBodyLinkColliderDoubleData -{ - btCollisionObjectDoubleData m_colObjData; - btMultiBodyDoubleData *m_multiBody; - int m_link; - char m_padding[4]; -}; - -SIMD_FORCE_INLINE int btMultiBodyLinkCollider::calculateSerializeBufferSize() const -{ - return sizeof(btMultiBodyLinkColliderData); -} - -SIMD_FORCE_INLINE const char* btMultiBodyLinkCollider::serialize(void* dataBuffer, class btSerializer* serializer) const -{ - btMultiBodyLinkColliderData* dataOut = (btMultiBodyLinkColliderData*)dataBuffer; - btCollisionObject::serialize(&dataOut->m_colObjData,serializer); - - dataOut->m_link = this->m_link; - dataOut->m_multiBody = (btMultiBodyData*)serializer->getUniquePointer(m_multiBody); - - // Fill padding with zeros to appease msan. - memset(dataOut->m_padding, 0, sizeof(dataOut->m_padding)); - - return btMultiBodyLinkColliderDataName; -} - #endif //BT_FEATHERSTONE_LINK_COLLIDER_H diff --git a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.cpp b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.cpp deleted file mode 100644 index 338e8af0ab5c..000000000000 --- a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.cpp +++ /dev/null @@ -1,966 +0,0 @@ -/* -Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2018 Google Inc. http://bulletphysics.org - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#include "BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h" - -#include "BulletCollision/NarrowPhaseCollision/btPersistentManifold.h" -#include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h" -#include "BulletDynamics/Featherstone/btMultiBodyConstraint.h" -#include "BulletDynamics/MLCPSolvers/btMLCPSolverInterface.h" - -#define DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS - -static bool interleaveContactAndFriction = false; - -struct btJointNode -{ - int jointIndex; // pointer to enclosing dxJoint object - int otherBodyIndex; // *other* body this joint is connected to - int nextJointNodeIndex; //-1 for null - int constraintRowIndex; -}; - -// Helper function to compute a delta velocity in the constraint space. -static btScalar computeDeltaVelocityInConstraintSpace( - const btVector3& angularDeltaVelocity, - const btVector3& contactNormal, - btScalar invMass, - const btVector3& angularJacobian, - const btVector3& linearJacobian) -{ - return angularDeltaVelocity.dot(angularJacobian) + contactNormal.dot(linearJacobian) * invMass; -} - -// Faster version of computeDeltaVelocityInConstraintSpace that can be used when contactNormal and linearJacobian are -// identical. -static btScalar computeDeltaVelocityInConstraintSpace( - const btVector3& angularDeltaVelocity, - btScalar invMass, - const btVector3& angularJacobian) -{ - return angularDeltaVelocity.dot(angularJacobian) + invMass; -} - -// Helper function to compute a delta velocity in the constraint space. -static btScalar computeDeltaVelocityInConstraintSpace(const btScalar* deltaVelocity, const btScalar* jacobian, int size) -{ - btScalar result = 0; - for (int i = 0; i < size; ++i) - result += deltaVelocity[i] * jacobian[i]; - - return result; -} - -static btScalar computeConstraintMatrixDiagElementMultiBody( - const btAlignedObjectArray& solverBodyPool, - const btMultiBodyJacobianData& data, - const btMultiBodySolverConstraint& constraint) -{ - btScalar ret = 0; - - const btMultiBody* multiBodyA = constraint.m_multiBodyA; - const btMultiBody* multiBodyB = constraint.m_multiBodyB; - - if (multiBodyA) - { - const btScalar* jacA = &data.m_jacobians[constraint.m_jacAindex]; - const btScalar* deltaA = &data.m_deltaVelocitiesUnitImpulse[constraint.m_jacAindex]; - const int ndofA = multiBodyA->getNumDofs() + 6; - ret += computeDeltaVelocityInConstraintSpace(deltaA, jacA, ndofA); - } - else - { - const int solverBodyIdA = constraint.m_solverBodyIdA; - btAssert(solverBodyIdA != -1); - const btSolverBody* solverBodyA = &solverBodyPool[solverBodyIdA]; - const btScalar invMassA = solverBodyA->m_originalBody ? solverBodyA->m_originalBody->getInvMass() : 0.0; - ret += computeDeltaVelocityInConstraintSpace( - constraint.m_relpos1CrossNormal, - invMassA, - constraint.m_angularComponentA); - } - - if (multiBodyB) - { - const btScalar* jacB = &data.m_jacobians[constraint.m_jacBindex]; - const btScalar* deltaB = &data.m_deltaVelocitiesUnitImpulse[constraint.m_jacBindex]; - const int ndofB = multiBodyB->getNumDofs() + 6; - ret += computeDeltaVelocityInConstraintSpace(deltaB, jacB, ndofB); - } - else - { - const int solverBodyIdB = constraint.m_solverBodyIdB; - btAssert(solverBodyIdB != -1); - const btSolverBody* solverBodyB = &solverBodyPool[solverBodyIdB]; - const btScalar invMassB = solverBodyB->m_originalBody ? solverBodyB->m_originalBody->getInvMass() : 0.0; - ret += computeDeltaVelocityInConstraintSpace( - constraint.m_relpos2CrossNormal, - invMassB, - constraint.m_angularComponentB); - } - - return ret; -} - -static btScalar computeConstraintMatrixOffDiagElementMultiBody( - const btAlignedObjectArray& solverBodyPool, - const btMultiBodyJacobianData& data, - const btMultiBodySolverConstraint& constraint, - const btMultiBodySolverConstraint& offDiagConstraint) -{ - btScalar offDiagA = btScalar(0); - - const btMultiBody* multiBodyA = constraint.m_multiBodyA; - const btMultiBody* multiBodyB = constraint.m_multiBodyB; - const btMultiBody* offDiagMultiBodyA = offDiagConstraint.m_multiBodyA; - const btMultiBody* offDiagMultiBodyB = offDiagConstraint.m_multiBodyB; - - // Assumed at least one system is multibody - btAssert(multiBodyA || multiBodyB); - btAssert(offDiagMultiBodyA || offDiagMultiBodyB); - - if (offDiagMultiBodyA) - { - const btScalar* offDiagJacA = &data.m_jacobians[offDiagConstraint.m_jacAindex]; - - if (offDiagMultiBodyA == multiBodyA) - { - const int ndofA = multiBodyA->getNumDofs() + 6; - const btScalar* deltaA = &data.m_deltaVelocitiesUnitImpulse[constraint.m_jacAindex]; - offDiagA += computeDeltaVelocityInConstraintSpace(deltaA, offDiagJacA, ndofA); - } - else if (offDiagMultiBodyA == multiBodyB) - { - const int ndofB = multiBodyB->getNumDofs() + 6; - const btScalar* deltaB = &data.m_deltaVelocitiesUnitImpulse[constraint.m_jacBindex]; - offDiagA += computeDeltaVelocityInConstraintSpace(deltaB, offDiagJacA, ndofB); - } - } - else - { - const int solverBodyIdA = constraint.m_solverBodyIdA; - const int solverBodyIdB = constraint.m_solverBodyIdB; - - const int offDiagSolverBodyIdA = offDiagConstraint.m_solverBodyIdA; - btAssert(offDiagSolverBodyIdA != -1); - - if (offDiagSolverBodyIdA == solverBodyIdA) - { - btAssert(solverBodyIdA != -1); - const btSolverBody* solverBodyA = &solverBodyPool[solverBodyIdA]; - const btScalar invMassA = solverBodyA->m_originalBody ? solverBodyA->m_originalBody->getInvMass() : 0.0; - offDiagA += computeDeltaVelocityInConstraintSpace( - offDiagConstraint.m_relpos1CrossNormal, - offDiagConstraint.m_contactNormal1, - invMassA, constraint.m_angularComponentA, - constraint.m_contactNormal1); - } - else if (offDiagSolverBodyIdA == solverBodyIdB) - { - btAssert(solverBodyIdB != -1); - const btSolverBody* solverBodyB = &solverBodyPool[solverBodyIdB]; - const btScalar invMassB = solverBodyB->m_originalBody ? solverBodyB->m_originalBody->getInvMass() : 0.0; - offDiagA += computeDeltaVelocityInConstraintSpace( - offDiagConstraint.m_relpos1CrossNormal, - offDiagConstraint.m_contactNormal1, - invMassB, - constraint.m_angularComponentB, - constraint.m_contactNormal2); - } - } - - if (offDiagMultiBodyB) - { - const btScalar* offDiagJacB = &data.m_jacobians[offDiagConstraint.m_jacBindex]; - - if (offDiagMultiBodyB == multiBodyA) - { - const int ndofA = multiBodyA->getNumDofs() + 6; - const btScalar* deltaA = &data.m_deltaVelocitiesUnitImpulse[constraint.m_jacAindex]; - offDiagA += computeDeltaVelocityInConstraintSpace(deltaA, offDiagJacB, ndofA); - } - else if (offDiagMultiBodyB == multiBodyB) - { - const int ndofB = multiBodyB->getNumDofs() + 6; - const btScalar* deltaB = &data.m_deltaVelocitiesUnitImpulse[constraint.m_jacBindex]; - offDiagA += computeDeltaVelocityInConstraintSpace(deltaB, offDiagJacB, ndofB); - } - } - else - { - const int solverBodyIdA = constraint.m_solverBodyIdA; - const int solverBodyIdB = constraint.m_solverBodyIdB; - - const int offDiagSolverBodyIdB = offDiagConstraint.m_solverBodyIdB; - btAssert(offDiagSolverBodyIdB != -1); - - if (offDiagSolverBodyIdB == solverBodyIdA) - { - btAssert(solverBodyIdA != -1); - const btSolverBody* solverBodyA = &solverBodyPool[solverBodyIdA]; - const btScalar invMassA = solverBodyA->m_originalBody ? solverBodyA->m_originalBody->getInvMass() : 0.0; - offDiagA += computeDeltaVelocityInConstraintSpace( - offDiagConstraint.m_relpos2CrossNormal, - offDiagConstraint.m_contactNormal2, - invMassA, constraint.m_angularComponentA, - constraint.m_contactNormal1); - } - else if (offDiagSolverBodyIdB == solverBodyIdB) - { - btAssert(solverBodyIdB != -1); - const btSolverBody* solverBodyB = &solverBodyPool[solverBodyIdB]; - const btScalar invMassB = solverBodyB->m_originalBody ? solverBodyB->m_originalBody->getInvMass() : 0.0; - offDiagA += computeDeltaVelocityInConstraintSpace( - offDiagConstraint.m_relpos2CrossNormal, - offDiagConstraint.m_contactNormal2, - invMassB, constraint.m_angularComponentB, - constraint.m_contactNormal2); - } - } - - return offDiagA; -} - -void btMultiBodyMLCPConstraintSolver::createMLCPFast(const btContactSolverInfo& infoGlobal) -{ - createMLCPFastRigidBody(infoGlobal); - createMLCPFastMultiBody(infoGlobal); -} - -void btMultiBodyMLCPConstraintSolver::createMLCPFastRigidBody(const btContactSolverInfo& infoGlobal) -{ - int numContactRows = interleaveContactAndFriction ? 3 : 1; - - int numConstraintRows = m_allConstraintPtrArray.size(); - - if (numConstraintRows == 0) - return; - - int n = numConstraintRows; - { - BT_PROFILE("init b (rhs)"); - m_b.resize(numConstraintRows); - m_bSplit.resize(numConstraintRows); - m_b.setZero(); - m_bSplit.setZero(); - for (int i = 0; i < numConstraintRows; i++) - { - btScalar jacDiag = m_allConstraintPtrArray[i]->m_jacDiagABInv; - if (!btFuzzyZero(jacDiag)) - { - btScalar rhs = m_allConstraintPtrArray[i]->m_rhs; - btScalar rhsPenetration = m_allConstraintPtrArray[i]->m_rhsPenetration; - m_b[i] = rhs / jacDiag; - m_bSplit[i] = rhsPenetration / jacDiag; - } - } - } - - // btScalar* w = 0; - // int nub = 0; - - m_lo.resize(numConstraintRows); - m_hi.resize(numConstraintRows); - - { - BT_PROFILE("init lo/ho"); - - for (int i = 0; i < numConstraintRows; i++) - { - if (0) //m_limitDependencies[i]>=0) - { - m_lo[i] = -BT_INFINITY; - m_hi[i] = BT_INFINITY; - } - else - { - m_lo[i] = m_allConstraintPtrArray[i]->m_lowerLimit; - m_hi[i] = m_allConstraintPtrArray[i]->m_upperLimit; - } - } - } - - // - int m = m_allConstraintPtrArray.size(); - - int numBodies = m_tmpSolverBodyPool.size(); - btAlignedObjectArray bodyJointNodeArray; - { - BT_PROFILE("bodyJointNodeArray.resize"); - bodyJointNodeArray.resize(numBodies, -1); - } - btAlignedObjectArray jointNodeArray; - { - BT_PROFILE("jointNodeArray.reserve"); - jointNodeArray.reserve(2 * m_allConstraintPtrArray.size()); - } - - btMatrixXu& J3 = m_scratchJ3; - { - BT_PROFILE("J3.resize"); - J3.resize(2 * m, 8); - } - btMatrixXu& JinvM3 = m_scratchJInvM3; - { - BT_PROFILE("JinvM3.resize/setZero"); - - JinvM3.resize(2 * m, 8); - JinvM3.setZero(); - J3.setZero(); - } - int cur = 0; - int rowOffset = 0; - btAlignedObjectArray& ofs = m_scratchOfs; - { - BT_PROFILE("ofs resize"); - ofs.resize(0); - ofs.resizeNoInitialize(m_allConstraintPtrArray.size()); - } - { - BT_PROFILE("Compute J and JinvM"); - int c = 0; - - int numRows = 0; - - for (int i = 0; i < m_allConstraintPtrArray.size(); i += numRows, c++) - { - ofs[c] = rowOffset; - int sbA = m_allConstraintPtrArray[i]->m_solverBodyIdA; - int sbB = m_allConstraintPtrArray[i]->m_solverBodyIdB; - btRigidBody* orgBodyA = m_tmpSolverBodyPool[sbA].m_originalBody; - btRigidBody* orgBodyB = m_tmpSolverBodyPool[sbB].m_originalBody; - - numRows = i < m_tmpSolverNonContactConstraintPool.size() ? m_tmpConstraintSizesPool[c].m_numConstraintRows : numContactRows; - if (orgBodyA) - { - { - int slotA = -1; - //find free jointNode slot for sbA - slotA = jointNodeArray.size(); - jointNodeArray.expand(); //NonInitializing(); - int prevSlot = bodyJointNodeArray[sbA]; - bodyJointNodeArray[sbA] = slotA; - jointNodeArray[slotA].nextJointNodeIndex = prevSlot; - jointNodeArray[slotA].jointIndex = c; - jointNodeArray[slotA].constraintRowIndex = i; - jointNodeArray[slotA].otherBodyIndex = orgBodyB ? sbB : -1; - } - for (int row = 0; row < numRows; row++, cur++) - { - btVector3 normalInvMass = m_allConstraintPtrArray[i + row]->m_contactNormal1 * orgBodyA->getInvMass(); - btVector3 relPosCrossNormalInvInertia = m_allConstraintPtrArray[i + row]->m_relpos1CrossNormal * orgBodyA->getInvInertiaTensorWorld(); - - for (int r = 0; r < 3; r++) - { - J3.setElem(cur, r, m_allConstraintPtrArray[i + row]->m_contactNormal1[r]); - J3.setElem(cur, r + 4, m_allConstraintPtrArray[i + row]->m_relpos1CrossNormal[r]); - JinvM3.setElem(cur, r, normalInvMass[r]); - JinvM3.setElem(cur, r + 4, relPosCrossNormalInvInertia[r]); - } - J3.setElem(cur, 3, 0); - JinvM3.setElem(cur, 3, 0); - J3.setElem(cur, 7, 0); - JinvM3.setElem(cur, 7, 0); - } - } - else - { - cur += numRows; - } - if (orgBodyB) - { - { - int slotB = -1; - //find free jointNode slot for sbA - slotB = jointNodeArray.size(); - jointNodeArray.expand(); //NonInitializing(); - int prevSlot = bodyJointNodeArray[sbB]; - bodyJointNodeArray[sbB] = slotB; - jointNodeArray[slotB].nextJointNodeIndex = prevSlot; - jointNodeArray[slotB].jointIndex = c; - jointNodeArray[slotB].otherBodyIndex = orgBodyA ? sbA : -1; - jointNodeArray[slotB].constraintRowIndex = i; - } - - for (int row = 0; row < numRows; row++, cur++) - { - btVector3 normalInvMassB = m_allConstraintPtrArray[i + row]->m_contactNormal2 * orgBodyB->getInvMass(); - btVector3 relPosInvInertiaB = m_allConstraintPtrArray[i + row]->m_relpos2CrossNormal * orgBodyB->getInvInertiaTensorWorld(); - - for (int r = 0; r < 3; r++) - { - J3.setElem(cur, r, m_allConstraintPtrArray[i + row]->m_contactNormal2[r]); - J3.setElem(cur, r + 4, m_allConstraintPtrArray[i + row]->m_relpos2CrossNormal[r]); - JinvM3.setElem(cur, r, normalInvMassB[r]); - JinvM3.setElem(cur, r + 4, relPosInvInertiaB[r]); - } - J3.setElem(cur, 3, 0); - JinvM3.setElem(cur, 3, 0); - J3.setElem(cur, 7, 0); - JinvM3.setElem(cur, 7, 0); - } - } - else - { - cur += numRows; - } - rowOffset += numRows; - } - } - - //compute JinvM = J*invM. - const btScalar* JinvM = JinvM3.getBufferPointer(); - - const btScalar* Jptr = J3.getBufferPointer(); - { - BT_PROFILE("m_A.resize"); - m_A.resize(n, n); - } - - { - BT_PROFILE("m_A.setZero"); - m_A.setZero(); - } - int c = 0; - { - int numRows = 0; - BT_PROFILE("Compute A"); - for (int i = 0; i < m_allConstraintPtrArray.size(); i += numRows, c++) - { - int row__ = ofs[c]; - int sbA = m_allConstraintPtrArray[i]->m_solverBodyIdA; - int sbB = m_allConstraintPtrArray[i]->m_solverBodyIdB; - // btRigidBody* orgBodyA = m_tmpSolverBodyPool[sbA].m_originalBody; - // btRigidBody* orgBodyB = m_tmpSolverBodyPool[sbB].m_originalBody; - - numRows = i < m_tmpSolverNonContactConstraintPool.size() ? m_tmpConstraintSizesPool[c].m_numConstraintRows : numContactRows; - - const btScalar* JinvMrow = JinvM + 2 * 8 * (size_t)row__; - - { - int startJointNodeA = bodyJointNodeArray[sbA]; - while (startJointNodeA >= 0) - { - int j0 = jointNodeArray[startJointNodeA].jointIndex; - int cr0 = jointNodeArray[startJointNodeA].constraintRowIndex; - if (j0 < c) - { - int numRowsOther = cr0 < m_tmpSolverNonContactConstraintPool.size() ? m_tmpConstraintSizesPool[j0].m_numConstraintRows : numContactRows; - size_t ofsother = (m_allConstraintPtrArray[cr0]->m_solverBodyIdB == sbA) ? 8 * numRowsOther : 0; - //printf("%d joint i %d and j0: %d: ",count++,i,j0); - m_A.multiplyAdd2_p8r(JinvMrow, - Jptr + 2 * 8 * (size_t)ofs[j0] + ofsother, numRows, numRowsOther, row__, ofs[j0]); - } - startJointNodeA = jointNodeArray[startJointNodeA].nextJointNodeIndex; - } - } - - { - int startJointNodeB = bodyJointNodeArray[sbB]; - while (startJointNodeB >= 0) - { - int j1 = jointNodeArray[startJointNodeB].jointIndex; - int cj1 = jointNodeArray[startJointNodeB].constraintRowIndex; - - if (j1 < c) - { - int numRowsOther = cj1 < m_tmpSolverNonContactConstraintPool.size() ? m_tmpConstraintSizesPool[j1].m_numConstraintRows : numContactRows; - size_t ofsother = (m_allConstraintPtrArray[cj1]->m_solverBodyIdB == sbB) ? 8 * numRowsOther : 0; - m_A.multiplyAdd2_p8r(JinvMrow + 8 * (size_t)numRows, - Jptr + 2 * 8 * (size_t)ofs[j1] + ofsother, numRows, numRowsOther, row__, ofs[j1]); - } - startJointNodeB = jointNodeArray[startJointNodeB].nextJointNodeIndex; - } - } - } - - { - BT_PROFILE("compute diagonal"); - // compute diagonal blocks of m_A - - int row__ = 0; - int numJointRows = m_allConstraintPtrArray.size(); - - int jj = 0; - for (; row__ < numJointRows;) - { - //int sbA = m_allConstraintPtrArray[row__]->m_solverBodyIdA; - int sbB = m_allConstraintPtrArray[row__]->m_solverBodyIdB; - // btRigidBody* orgBodyA = m_tmpSolverBodyPool[sbA].m_originalBody; - btRigidBody* orgBodyB = m_tmpSolverBodyPool[sbB].m_originalBody; - - const unsigned int infom = row__ < m_tmpSolverNonContactConstraintPool.size() ? m_tmpConstraintSizesPool[jj].m_numConstraintRows : numContactRows; - - const btScalar* JinvMrow = JinvM + 2 * 8 * (size_t)row__; - const btScalar* Jrow = Jptr + 2 * 8 * (size_t)row__; - m_A.multiply2_p8r(JinvMrow, Jrow, infom, infom, row__, row__); - if (orgBodyB) - { - m_A.multiplyAdd2_p8r(JinvMrow + 8 * (size_t)infom, Jrow + 8 * (size_t)infom, infom, infom, row__, row__); - } - row__ += infom; - jj++; - } - } - } - - if (1) - { - // add cfm to the diagonal of m_A - for (int i = 0; i < m_A.rows(); ++i) - { - m_A.setElem(i, i, m_A(i, i) + infoGlobal.m_globalCfm / infoGlobal.m_timeStep); - } - } - - ///fill the upper triangle of the matrix, to make it symmetric - { - BT_PROFILE("fill the upper triangle "); - m_A.copyLowerToUpperTriangle(); - } - - { - BT_PROFILE("resize/init x"); - m_x.resize(numConstraintRows); - m_xSplit.resize(numConstraintRows); - - if (infoGlobal.m_solverMode & SOLVER_USE_WARMSTARTING) - { - for (int i = 0; i < m_allConstraintPtrArray.size(); i++) - { - const btSolverConstraint& c = *m_allConstraintPtrArray[i]; - m_x[i] = c.m_appliedImpulse; - m_xSplit[i] = c.m_appliedPushImpulse; - } - } - else - { - m_x.setZero(); - m_xSplit.setZero(); - } - } -} - -void btMultiBodyMLCPConstraintSolver::createMLCPFastMultiBody(const btContactSolverInfo& infoGlobal) -{ - const int multiBodyNumConstraints = m_multiBodyAllConstraintPtrArray.size(); - - if (multiBodyNumConstraints == 0) - return; - - // 1. Compute b - { - BT_PROFILE("init b (rhs)"); - - m_multiBodyB.resize(multiBodyNumConstraints); - m_multiBodyB.setZero(); - - for (int i = 0; i < multiBodyNumConstraints; ++i) - { - const btMultiBodySolverConstraint& constraint = *m_multiBodyAllConstraintPtrArray[i]; - const btScalar jacDiag = constraint.m_jacDiagABInv; - - if (!btFuzzyZero(jacDiag)) - { - // Note that rhsPenetration is currently always zero because the split impulse hasn't been implemented for multibody yet. - const btScalar rhs = constraint.m_rhs; - m_multiBodyB[i] = rhs / jacDiag; - } - } - } - - // 2. Compute lo and hi - { - BT_PROFILE("init lo/ho"); - - m_multiBodyLo.resize(multiBodyNumConstraints); - m_multiBodyHi.resize(multiBodyNumConstraints); - - for (int i = 0; i < multiBodyNumConstraints; ++i) - { - const btMultiBodySolverConstraint& constraint = *m_multiBodyAllConstraintPtrArray[i]; - m_multiBodyLo[i] = constraint.m_lowerLimit; - m_multiBodyHi[i] = constraint.m_upperLimit; - } - } - - // 3. Construct A matrix by using the impulse testing - { - BT_PROFILE("Compute A"); - - { - BT_PROFILE("m_A.resize"); - m_multiBodyA.resize(multiBodyNumConstraints, multiBodyNumConstraints); - } - - for (int i = 0; i < multiBodyNumConstraints; ++i) - { - // Compute the diagonal of A, which is A(i, i) - const btMultiBodySolverConstraint& constraint = *m_multiBodyAllConstraintPtrArray[i]; - const btScalar diagA = computeConstraintMatrixDiagElementMultiBody(m_tmpSolverBodyPool, m_data, constraint); - m_multiBodyA.setElem(i, i, diagA); - - // Computes the off-diagonals of A: - // a. The rest of i-th row of A, from A(i, i+1) to A(i, n) - // b. The rest of i-th column of A, from A(i+1, i) to A(n, i) - for (int j = i + 1; j < multiBodyNumConstraints; ++j) - { - const btMultiBodySolverConstraint& offDiagConstraint = *m_multiBodyAllConstraintPtrArray[j]; - const btScalar offDiagA = computeConstraintMatrixOffDiagElementMultiBody(m_tmpSolverBodyPool, m_data, constraint, offDiagConstraint); - - // Set the off-diagonal values of A. Note that A is symmetric. - m_multiBodyA.setElem(i, j, offDiagA); - m_multiBodyA.setElem(j, i, offDiagA); - } - } - } - - // Add CFM to the diagonal of m_A - for (int i = 0; i < m_multiBodyA.rows(); ++i) - { - m_multiBodyA.setElem(i, i, m_multiBodyA(i, i) + infoGlobal.m_globalCfm / infoGlobal.m_timeStep); - } - - // 4. Initialize x - { - BT_PROFILE("resize/init x"); - - m_multiBodyX.resize(multiBodyNumConstraints); - - if (infoGlobal.m_solverMode & SOLVER_USE_WARMSTARTING) - { - for (int i = 0; i < multiBodyNumConstraints; ++i) - { - const btMultiBodySolverConstraint& constraint = *m_multiBodyAllConstraintPtrArray[i]; - m_multiBodyX[i] = constraint.m_appliedImpulse; - } - } - else - { - m_multiBodyX.setZero(); - } - } -} - -bool btMultiBodyMLCPConstraintSolver::solveMLCP(const btContactSolverInfo& infoGlobal) -{ - bool result = true; - - if (m_A.rows() != 0) - { - // If using split impulse, we solve 2 separate (M)LCPs - if (infoGlobal.m_splitImpulse) - { - const btMatrixXu Acopy = m_A; - const btAlignedObjectArray limitDependenciesCopy = m_limitDependencies; - // TODO(JS): Do we really need these copies when solveMLCP takes them as const? - - result = m_solver->solveMLCP(m_A, m_b, m_x, m_lo, m_hi, m_limitDependencies, infoGlobal.m_numIterations); - if (result) - result = m_solver->solveMLCP(Acopy, m_bSplit, m_xSplit, m_lo, m_hi, limitDependenciesCopy, infoGlobal.m_numIterations); - } - else - { - result = m_solver->solveMLCP(m_A, m_b, m_x, m_lo, m_hi, m_limitDependencies, infoGlobal.m_numIterations); - } - } - - if (!result) - return false; - - if (m_multiBodyA.rows() != 0) - { - result = m_solver->solveMLCP(m_multiBodyA, m_multiBodyB, m_multiBodyX, m_multiBodyLo, m_multiBodyHi, m_multiBodyLimitDependencies, infoGlobal.m_numIterations); - } - - return result; -} - -btScalar btMultiBodyMLCPConstraintSolver::solveGroupCacheFriendlySetup( - btCollisionObject** bodies, - int numBodies, - btPersistentManifold** manifoldPtr, - int numManifolds, - btTypedConstraint** constraints, - int numConstraints, - const btContactSolverInfo& infoGlobal, - btIDebugDraw* debugDrawer) -{ - // 1. Setup for rigid-bodies - btMultiBodyConstraintSolver::solveGroupCacheFriendlySetup( - bodies, numBodies, manifoldPtr, numManifolds, constraints, numConstraints, infoGlobal, debugDrawer); - - // 2. Setup for multi-bodies - // a. Collect all different kinds of constraint as pointers into one array, m_allConstraintPtrArray - // b. Set the index array for frictional contact constraints, m_limitDependencies - { - BT_PROFILE("gather constraint data"); - - int dindex = 0; - - const int numRigidBodyConstraints = m_tmpSolverNonContactConstraintPool.size() + m_tmpSolverContactConstraintPool.size() + m_tmpSolverContactFrictionConstraintPool.size(); - const int numMultiBodyConstraints = m_multiBodyNonContactConstraints.size() + m_multiBodyNormalContactConstraints.size() + m_multiBodyFrictionContactConstraints.size(); - - m_allConstraintPtrArray.resize(0); - m_multiBodyAllConstraintPtrArray.resize(0); - - // i. Setup for rigid bodies - - m_limitDependencies.resize(numRigidBodyConstraints); - - for (int i = 0; i < m_tmpSolverNonContactConstraintPool.size(); ++i) - { - m_allConstraintPtrArray.push_back(&m_tmpSolverNonContactConstraintPool[i]); - m_limitDependencies[dindex++] = -1; - } - - int firstContactConstraintOffset = dindex; - - // The btSequentialImpulseConstraintSolver moves all friction constraints at the very end, we can also interleave them instead - if (interleaveContactAndFriction) - { - for (int i = 0; i < m_tmpSolverContactConstraintPool.size(); i++) - { - const int numFrictionPerContact = m_tmpSolverContactConstraintPool.size() == m_tmpSolverContactFrictionConstraintPool.size() ? 1 : 2; - - m_allConstraintPtrArray.push_back(&m_tmpSolverContactConstraintPool[i]); - m_limitDependencies[dindex++] = -1; - m_allConstraintPtrArray.push_back(&m_tmpSolverContactFrictionConstraintPool[i * numFrictionPerContact]); - int findex = (m_tmpSolverContactFrictionConstraintPool[i * numFrictionPerContact].m_frictionIndex * (1 + numFrictionPerContact)); - m_limitDependencies[dindex++] = findex + firstContactConstraintOffset; - if (numFrictionPerContact == 2) - { - m_allConstraintPtrArray.push_back(&m_tmpSolverContactFrictionConstraintPool[i * numFrictionPerContact + 1]); - m_limitDependencies[dindex++] = findex + firstContactConstraintOffset; - } - } - } - else - { - for (int i = 0; i < m_tmpSolverContactConstraintPool.size(); i++) - { - m_allConstraintPtrArray.push_back(&m_tmpSolverContactConstraintPool[i]); - m_limitDependencies[dindex++] = -1; - } - for (int i = 0; i < m_tmpSolverContactFrictionConstraintPool.size(); i++) - { - m_allConstraintPtrArray.push_back(&m_tmpSolverContactFrictionConstraintPool[i]); - m_limitDependencies[dindex++] = m_tmpSolverContactFrictionConstraintPool[i].m_frictionIndex + firstContactConstraintOffset; - } - } - - if (!m_allConstraintPtrArray.size()) - { - m_A.resize(0, 0); - m_b.resize(0); - m_x.resize(0); - m_lo.resize(0); - m_hi.resize(0); - } - - // ii. Setup for multibodies - - dindex = 0; - - m_multiBodyLimitDependencies.resize(numMultiBodyConstraints); - - for (int i = 0; i < m_multiBodyNonContactConstraints.size(); ++i) - { - m_multiBodyAllConstraintPtrArray.push_back(&m_multiBodyNonContactConstraints[i]); - m_multiBodyLimitDependencies[dindex++] = -1; - } - - firstContactConstraintOffset = dindex; - - // The btSequentialImpulseConstraintSolver moves all friction constraints at the very end, we can also interleave them instead - if (interleaveContactAndFriction) - { - for (int i = 0; i < m_multiBodyNormalContactConstraints.size(); ++i) - { - const int numtiBodyNumFrictionPerContact = m_multiBodyNormalContactConstraints.size() == m_multiBodyFrictionContactConstraints.size() ? 1 : 2; - - m_multiBodyAllConstraintPtrArray.push_back(&m_multiBodyNormalContactConstraints[i]); - m_multiBodyLimitDependencies[dindex++] = -1; - - btMultiBodySolverConstraint& frictionContactConstraint1 = m_multiBodyFrictionContactConstraints[i * numtiBodyNumFrictionPerContact]; - m_multiBodyAllConstraintPtrArray.push_back(&frictionContactConstraint1); - - const int findex = (frictionContactConstraint1.m_frictionIndex * (1 + numtiBodyNumFrictionPerContact)) + firstContactConstraintOffset; - - m_multiBodyLimitDependencies[dindex++] = findex; - - if (numtiBodyNumFrictionPerContact == 2) - { - btMultiBodySolverConstraint& frictionContactConstraint2 = m_multiBodyFrictionContactConstraints[i * numtiBodyNumFrictionPerContact + 1]; - m_multiBodyAllConstraintPtrArray.push_back(&frictionContactConstraint2); - - m_multiBodyLimitDependencies[dindex++] = findex; - } - } - } - else - { - for (int i = 0; i < m_multiBodyNormalContactConstraints.size(); ++i) - { - m_multiBodyAllConstraintPtrArray.push_back(&m_multiBodyNormalContactConstraints[i]); - m_multiBodyLimitDependencies[dindex++] = -1; - } - for (int i = 0; i < m_multiBodyFrictionContactConstraints.size(); ++i) - { - m_multiBodyAllConstraintPtrArray.push_back(&m_multiBodyFrictionContactConstraints[i]); - m_multiBodyLimitDependencies[dindex++] = m_multiBodyFrictionContactConstraints[i].m_frictionIndex + firstContactConstraintOffset; - } - } - - if (!m_multiBodyAllConstraintPtrArray.size()) - { - m_multiBodyA.resize(0, 0); - m_multiBodyB.resize(0); - m_multiBodyX.resize(0); - m_multiBodyLo.resize(0); - m_multiBodyHi.resize(0); - } - } - - // Construct MLCP terms - { - BT_PROFILE("createMLCPFast"); - createMLCPFast(infoGlobal); - } - - return btScalar(0); -} - -btScalar btMultiBodyMLCPConstraintSolver::solveGroupCacheFriendlyIterations(btCollisionObject** bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer) -{ - bool result = true; - { - BT_PROFILE("solveMLCP"); - result = solveMLCP(infoGlobal); - } - - // Fallback to btSequentialImpulseConstraintSolver::solveGroupCacheFriendlyIterations if the solution isn't valid. - if (!result) - { - m_fallback++; - return btMultiBodyConstraintSolver::solveGroupCacheFriendlyIterations(bodies, numBodies, manifoldPtr, numManifolds, constraints, numConstraints, infoGlobal, debugDrawer); - } - - { - BT_PROFILE("process MLCP results"); - - for (int i = 0; i < m_allConstraintPtrArray.size(); ++i) - { - const btSolverConstraint& c = *m_allConstraintPtrArray[i]; - - const btScalar deltaImpulse = m_x[i] - c.m_appliedImpulse; - c.m_appliedImpulse = m_x[i]; - - int sbA = c.m_solverBodyIdA; - int sbB = c.m_solverBodyIdB; - - btSolverBody& solverBodyA = m_tmpSolverBodyPool[sbA]; - btSolverBody& solverBodyB = m_tmpSolverBodyPool[sbB]; - - solverBodyA.internalApplyImpulse(c.m_contactNormal1 * solverBodyA.internalGetInvMass(), c.m_angularComponentA, deltaImpulse); - solverBodyB.internalApplyImpulse(c.m_contactNormal2 * solverBodyB.internalGetInvMass(), c.m_angularComponentB, deltaImpulse); - - if (infoGlobal.m_splitImpulse) - { - const btScalar deltaPushImpulse = m_xSplit[i] - c.m_appliedPushImpulse; - solverBodyA.internalApplyPushImpulse(c.m_contactNormal1 * solverBodyA.internalGetInvMass(), c.m_angularComponentA, deltaPushImpulse); - solverBodyB.internalApplyPushImpulse(c.m_contactNormal2 * solverBodyB.internalGetInvMass(), c.m_angularComponentB, deltaPushImpulse); - c.m_appliedPushImpulse = m_xSplit[i]; - } - } - - for (int i = 0; i < m_multiBodyAllConstraintPtrArray.size(); ++i) - { - btMultiBodySolverConstraint& c = *m_multiBodyAllConstraintPtrArray[i]; - - const btScalar deltaImpulse = m_multiBodyX[i] - c.m_appliedImpulse; - c.m_appliedImpulse = m_multiBodyX[i]; - - btMultiBody* multiBodyA = c.m_multiBodyA; - if (multiBodyA) - { - const int ndofA = multiBodyA->getNumDofs() + 6; - applyDeltaVee(&m_data.m_deltaVelocitiesUnitImpulse[c.m_jacAindex], deltaImpulse, c.m_deltaVelAindex, ndofA); -#ifdef DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS - //note: update of the actual velocities (below) in the multibody does not have to happen now since m_deltaVelocities can be applied after all iterations - //it would make the multibody solver more like the regular one with m_deltaVelocities being equivalent to btSolverBody::m_deltaLinearVelocity/m_deltaAngularVelocity - multiBodyA->applyDeltaVeeMultiDof2(&m_data.m_deltaVelocitiesUnitImpulse[c.m_jacAindex], deltaImpulse); -#endif // DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS - } - else - { - const int sbA = c.m_solverBodyIdA; - btSolverBody& solverBodyA = m_tmpSolverBodyPool[sbA]; - solverBodyA.internalApplyImpulse(c.m_contactNormal1 * solverBodyA.internalGetInvMass(), c.m_angularComponentA, deltaImpulse); - } - - btMultiBody* multiBodyB = c.m_multiBodyB; - if (multiBodyB) - { - const int ndofB = multiBodyB->getNumDofs() + 6; - applyDeltaVee(&m_data.m_deltaVelocitiesUnitImpulse[c.m_jacBindex], deltaImpulse, c.m_deltaVelBindex, ndofB); -#ifdef DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS - //note: update of the actual velocities (below) in the multibody does not have to happen now since m_deltaVelocities can be applied after all iterations - //it would make the multibody solver more like the regular one with m_deltaVelocities being equivalent to btSolverBody::m_deltaLinearVelocity/m_deltaAngularVelocity - multiBodyB->applyDeltaVeeMultiDof2(&m_data.m_deltaVelocitiesUnitImpulse[c.m_jacBindex], deltaImpulse); -#endif // DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS - } - else - { - const int sbB = c.m_solverBodyIdB; - btSolverBody& solverBodyB = m_tmpSolverBodyPool[sbB]; - solverBodyB.internalApplyImpulse(c.m_contactNormal2 * solverBodyB.internalGetInvMass(), c.m_angularComponentB, deltaImpulse); - } - } - } - - return btScalar(0); -} - -btMultiBodyMLCPConstraintSolver::btMultiBodyMLCPConstraintSolver(btMLCPSolverInterface* solver) - : m_solver(solver), m_fallback(0) -{ - // Do nothing -} - -btMultiBodyMLCPConstraintSolver::~btMultiBodyMLCPConstraintSolver() -{ - // Do nothing -} - -void btMultiBodyMLCPConstraintSolver::setMLCPSolver(btMLCPSolverInterface* solver) -{ - m_solver = solver; -} - -int btMultiBodyMLCPConstraintSolver::getNumFallbacks() const -{ - return m_fallback; -} - -void btMultiBodyMLCPConstraintSolver::setNumFallbacks(int num) -{ - m_fallback = num; -} - -btConstraintSolverType btMultiBodyMLCPConstraintSolver::getSolverType() const -{ - return BT_MLCP_SOLVER; -} diff --git a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h b/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h deleted file mode 100644 index 6be36ba142e5..000000000000 --- a/extern/bullet/src/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h +++ /dev/null @@ -1,187 +0,0 @@ -/* -Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2018 Google Inc. http://bulletphysics.org - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#ifndef BT_MULTIBODY_MLCP_CONSTRAINT_SOLVER_H -#define BT_MULTIBODY_MLCP_CONSTRAINT_SOLVER_H - -#include "LinearMath/btMatrixX.h" -#include "LinearMath/btThreads.h" -#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" - -class btMLCPSolverInterface; -class btMultiBody; - -class btMultiBodyMLCPConstraintSolver : public btMultiBodyConstraintSolver -{ -protected: - /// \name MLCP Formulation for Rigid Bodies - /// \{ - - /// A matrix in the MLCP formulation - btMatrixXu m_A; - - /// b vector in the MLCP formulation. - btVectorXu m_b; - - /// Constraint impulse, which is an output of MLCP solving. - btVectorXu m_x; - - /// Lower bound of constraint impulse, \c m_x. - btVectorXu m_lo; - - /// Upper bound of constraint impulse, \c m_x. - btVectorXu m_hi; - - /// \} - - /// \name Cache Variables for Split Impulse for Rigid Bodies - /// When using 'split impulse' we solve two separate (M)LCPs - /// \{ - - /// Split impulse Cache vector corresponding to \c m_b. - btVectorXu m_bSplit; - - /// Split impulse cache vector corresponding to \c m_x. - btVectorXu m_xSplit; - - /// \} - - /// \name MLCP Formulation for Multibodies - /// \{ - - /// A matrix in the MLCP formulation - btMatrixXu m_multiBodyA; - - /// b vector in the MLCP formulation. - btVectorXu m_multiBodyB; - - /// Constraint impulse, which is an output of MLCP solving. - btVectorXu m_multiBodyX; - - /// Lower bound of constraint impulse, \c m_x. - btVectorXu m_multiBodyLo; - - /// Upper bound of constraint impulse, \c m_x. - btVectorXu m_multiBodyHi; - - /// \} - - /// Indices of normal contact constraint associated with frictional contact constraint for rigid bodies. - /// - /// This is used by the MLCP solver to update the upper bounds of frictional contact impulse given intermediate - /// normal contact impulse. For example, i-th element represents the index of a normal constraint that is - /// accosiated with i-th frictional contact constraint if i-th constraint is a frictional contact constraint. - /// Otherwise, -1. - btAlignedObjectArray m_limitDependencies; - - /// Indices of normal contact constraint associated with frictional contact constraint for multibodies. - /// - /// This is used by the MLCP solver to update the upper bounds of frictional contact impulse given intermediate - /// normal contact impulse. For example, i-th element represents the index of a normal constraint that is - /// accosiated with i-th frictional contact constraint if i-th constraint is a frictional contact constraint. - /// Otherwise, -1. - btAlignedObjectArray m_multiBodyLimitDependencies; - - /// Array of all the rigid body constraints - btAlignedObjectArray m_allConstraintPtrArray; - - /// Array of all the multibody constraints - btAlignedObjectArray m_multiBodyAllConstraintPtrArray; - - /// MLCP solver - btMLCPSolverInterface* m_solver; - - /// Count of fallbacks of using btSequentialImpulseConstraintSolver, which happens when the MLCP solver fails. - int m_fallback; - - /// \name MLCP Scratch Variables - /// The following scratch variables are not stateful -- contents are cleared prior to each use. - /// They are only cached here to avoid extra memory allocations and deallocations and to ensure - /// that multiple instances of the solver can be run in parallel. - /// - /// \{ - - /// Cache variable for constraint Jacobian matrix. - btMatrixXu m_scratchJ3; - - /// Cache variable for constraint Jacobian times inverse mass matrix. - btMatrixXu m_scratchJInvM3; - - /// Cache variable for offsets. - btAlignedObjectArray m_scratchOfs; - - /// \} - - /// Constructs MLCP terms, which are \c m_A, \c m_b, \c m_lo, and \c m_hi. - virtual void createMLCPFast(const btContactSolverInfo& infoGlobal); - - /// Constructs MLCP terms for constraints of two rigid bodies - void createMLCPFastRigidBody(const btContactSolverInfo& infoGlobal); - - /// Constructs MLCP terms for constraints of two multi-bodies or one rigid body and one multibody - void createMLCPFastMultiBody(const btContactSolverInfo& infoGlobal); - - /// Solves MLCP and returns the success - virtual bool solveMLCP(const btContactSolverInfo& infoGlobal); - - // Documentation inherited - btScalar solveGroupCacheFriendlySetup( - btCollisionObject** bodies, - int numBodies, - btPersistentManifold** manifoldPtr, - int numManifolds, - btTypedConstraint** constraints, - int numConstraints, - const btContactSolverInfo& infoGlobal, - btIDebugDraw* debugDrawer) BT_OVERRIDE; - - // Documentation inherited - btScalar solveGroupCacheFriendlyIterations( - btCollisionObject** bodies, - int numBodies, - btPersistentManifold** manifoldPtr, - int numManifolds, - btTypedConstraint** constraints, - int numConstraints, - const btContactSolverInfo& infoGlobal, - btIDebugDraw* debugDrawer) BT_OVERRIDE; - -public: - BT_DECLARE_ALIGNED_ALLOCATOR() - - /// Constructor - /// - /// \param[in] solver MLCP solver. Assumed it's not null. - /// \param[in] maxLCPSize Maximum size of LCP to solve using MLCP solver. If the MLCP size exceeds this number, sequaltial impulse method will be used. - explicit btMultiBodyMLCPConstraintSolver(btMLCPSolverInterface* solver); - - /// Destructor - virtual ~btMultiBodyMLCPConstraintSolver(); - - /// Sets MLCP solver. Assumed it's not null. - void setMLCPSolver(btMLCPSolverInterface* solver); - - /// Returns the number of fallbacks of using btSequentialImpulseConstraintSolver, which happens when the MLCP - /// solver fails. - int getNumFallbacks() const; - - /// Sets the number of fallbacks. This function may be used to reset the number to zero. - void setNumFallbacks(int num); - - /// Returns the constraint solver type. - virtual btConstraintSolverType getSolverType() const; -}; - -#endif // BT_MULTIBODY_MLCP_CONSTRAINT_SOLVER_H diff --git a/extern/bullet/src/BulletDynamics/Vehicle/btRaycastVehicle.cpp b/extern/bullet/src/BulletDynamics/Vehicle/btRaycastVehicle.cpp index f299aa34e8d4..a7b1688469fd 100644 --- a/extern/bullet/src/BulletDynamics/Vehicle/btRaycastVehicle.cpp +++ b/extern/bullet/src/BulletDynamics/Vehicle/btRaycastVehicle.cpp @@ -121,19 +121,12 @@ void btRaycastVehicle::updateWheelTransform( int wheelIndex , bool interpolatedT btQuaternion rotatingOrn(right,-wheel.m_rotation); btMatrix3x3 rotatingMat(rotatingOrn); - btMatrix3x3 basis2; - basis2[0][m_indexRightAxis] = -right[0]; - basis2[1][m_indexRightAxis] = -right[1]; - basis2[2][m_indexRightAxis] = -right[2]; - - basis2[0][m_indexUpAxis] = up[0]; - basis2[1][m_indexUpAxis] = up[1]; - basis2[2][m_indexUpAxis] = up[2]; - - basis2[0][m_indexForwardAxis] = fwd[0]; - basis2[1][m_indexForwardAxis] = fwd[1]; - basis2[2][m_indexForwardAxis] = fwd[2]; - + btMatrix3x3 basis2( + right[0],fwd[0],up[0], + right[1],fwd[1],up[1], + right[2],fwd[2],up[2] + ); + wheel.m_worldTransform.setBasis(steeringMat * rotatingMat * basis2); wheel.m_worldTransform.setOrigin( wheel.m_raycastInfo.m_hardPointWS + wheel.m_raycastInfo.m_wheelDirectionWS * wheel.m_raycastInfo.m_suspensionLength @@ -500,8 +493,8 @@ struct btWheelContactPoint }; -btScalar calcRollingFriction(btWheelContactPoint& contactPoint, int numWheelsOnGround); -btScalar calcRollingFriction(btWheelContactPoint& contactPoint, int numWheelsOnGround) +btScalar calcRollingFriction(btWheelContactPoint& contactPoint); +btScalar calcRollingFriction(btWheelContactPoint& contactPoint) { btScalar j1=0.f; @@ -520,7 +513,7 @@ btScalar calcRollingFriction(btWheelContactPoint& contactPoint, int numWheelsOnG btScalar vrel = contactPoint.m_frictionDirectionWorld.dot(vel); // calculate j that moves us to zero relative velocity - j1 = -vrel * contactPoint.m_jacDiagABInv/btScalar(numWheelsOnGround); + j1 = -vrel * contactPoint.m_jacDiagABInv; btSetMin(j1, maxImpulse); btSetMax(j1, -maxImpulse); @@ -574,7 +567,7 @@ void btRaycastVehicle::updateFriction(btScalar timeStep) const btTransform& wheelTrans = getWheelTransformWS( i ); btMatrix3x3 wheelBasis0 = wheelTrans.getBasis(); - m_axle[i] = -btVector3( + m_axle[i] = btVector3( wheelBasis0[0][m_indexRightAxis], wheelBasis0[1][m_indexRightAxis], wheelBasis0[2][m_indexRightAxis]); @@ -622,8 +615,7 @@ void btRaycastVehicle::updateFriction(btScalar timeStep) btScalar defaultRollingFrictionImpulse = 0.f; btScalar maxImpulse = wheelInfo.m_brake ? wheelInfo.m_brake : defaultRollingFrictionImpulse; btWheelContactPoint contactPt(m_chassisBody,groundObject,wheelInfo.m_raycastInfo.m_contactPointWS,m_forwardWS[wheel],maxImpulse); - btAssert(numWheelsOnGround > 0); - rollingFriction = calcRollingFriction(contactPt, numWheelsOnGround); + rollingFriction = calcRollingFriction(contactPt); } } diff --git a/extern/bullet/src/BulletDynamics/premake4.lua b/extern/bullet/src/BulletDynamics/premake4.lua index fdaf0513d896..32414dce3eab 100644 --- a/extern/bullet/src/BulletDynamics/premake4.lua +++ b/extern/bullet/src/BulletDynamics/premake4.lua @@ -3,9 +3,6 @@ includedirs { "..", } - if os.is("Linux") then - buildoptions{"-fPIC"} - end files { "Dynamics/*.cpp", "Dynamics/*.h", diff --git a/extern/bullet/src/BulletInverseDynamics/IDErrorMessages.hpp b/extern/bullet/src/BulletInverseDynamics/IDErrorMessages.hpp index 1b3fd268a0b9..1dc22f860ab6 100644 --- a/extern/bullet/src/BulletInverseDynamics/IDErrorMessages.hpp +++ b/extern/bullet/src/BulletInverseDynamics/IDErrorMessages.hpp @@ -7,19 +7,19 @@ #if !defined(BT_ID_WO_BULLET) && !defined(BT_USE_INVERSE_DYNAMICS_WITH_BULLET2) #include "Bullet3Common/b3Logging.h" -#define bt_id_error_message(...) b3Error(__VA_ARGS__) -#define bt_id_warning_message(...) b3Warning(__VA_ARGS__) +#define error_message(...) b3Error(__VA_ARGS__) +#define warning_message(...) b3Warning(__VA_ARGS__) #define id_printf(...) b3Printf(__VA_ARGS__) #else // BT_ID_WO_BULLET #include /// print error message with file/line information -#define bt_id_error_message(...) \ +#define error_message(...) \ do { \ fprintf(stderr, "[Error:%s:%d] ", __INVDYN_FILE_WO_DIR__, __LINE__); \ fprintf(stderr, __VA_ARGS__); \ } while (0) /// print warning message with file/line information -#define bt_id_warning_message(...) \ +#define warning_message(...) \ do { \ fprintf(stderr, "[Warning:%s:%d] ", __INVDYN_FILE_WO_DIR__, __LINE__); \ fprintf(stderr, __VA_ARGS__); \ diff --git a/extern/bullet/src/BulletInverseDynamics/IDMath.cpp b/extern/bullet/src/BulletInverseDynamics/IDMath.cpp index d279d3435c6b..99fe20e49287 100644 --- a/extern/bullet/src/BulletInverseDynamics/IDMath.cpp +++ b/extern/bullet/src/BulletInverseDynamics/IDMath.cpp @@ -81,7 +81,7 @@ idScalar maxAbsMat3x(const mat3x &m) { void mul(const mat33 &a, const mat3x &b, mat3x *result) { if (b.cols() != result->cols()) { - bt_id_error_message("size missmatch. b.cols()= %d, result->cols()= %d\n", + error_message("size missmatch. b.cols()= %d, result->cols()= %d\n", static_cast(b.cols()), static_cast(result->cols())); abort(); } @@ -97,7 +97,7 @@ void mul(const mat33 &a, const mat3x &b, mat3x *result) { } void add(const mat3x &a, const mat3x &b, mat3x *result) { if (a.cols() != b.cols()) { - bt_id_error_message("size missmatch. a.cols()= %d, b.cols()= %d\n", + error_message("size missmatch. a.cols()= %d, b.cols()= %d\n", static_cast(a.cols()), static_cast(b.cols())); abort(); } @@ -109,7 +109,7 @@ void add(const mat3x &a, const mat3x &b, mat3x *result) { } void sub(const mat3x &a, const mat3x &b, mat3x *result) { if (a.cols() != b.cols()) { - bt_id_error_message("size missmatch. a.cols()= %d, b.cols()= %d\n", + error_message("size missmatch. a.cols()= %d, b.cols()= %d\n", static_cast(a.cols()), static_cast(b.cols())); abort(); } @@ -305,10 +305,10 @@ bool isValidInertiaMatrix(const mat33 &I, const int index, bool has_fixed_joint) // the determinant of the inertia tensor about the joint axis is almost // zero and can have a very small negative value. if (!isPositiveSemiDefiniteFuzzy(I)) { - bt_id_error_message("invalid inertia matrix for body %d, not positive definite " + error_message("invalid inertia matrix for body %d, not positive definite " "(fixed joint)\n", index); - bt_id_error_message("matrix is:\n" + error_message("matrix is:\n" "[%.20e %.20e %.20e;\n" "%.20e %.20e %.20e;\n" "%.20e %.20e %.20e]\n", @@ -321,8 +321,8 @@ bool isValidInertiaMatrix(const mat33 &I, const int index, bool has_fixed_joint) // check triangle inequality, must have I(i,i)+I(j,j)>=I(k,k) if (!has_fixed_joint) { if (I(0, 0) + I(1, 1) < I(2, 2)) { - bt_id_error_message("invalid inertia tensor for body %d, I(0,0) + I(1,1) < I(2,2)\n", index); - bt_id_error_message("matrix is:\n" + error_message("invalid inertia tensor for body %d, I(0,0) + I(1,1) < I(2,2)\n", index); + error_message("matrix is:\n" "[%.20e %.20e %.20e;\n" "%.20e %.20e %.20e;\n" "%.20e %.20e %.20e]\n", @@ -331,8 +331,8 @@ bool isValidInertiaMatrix(const mat33 &I, const int index, bool has_fixed_joint) return false; } if (I(0, 0) + I(1, 1) < I(2, 2)) { - bt_id_error_message("invalid inertia tensor for body %d, I(0,0) + I(1,1) < I(2,2)\n", index); - bt_id_error_message("matrix is:\n" + error_message("invalid inertia tensor for body %d, I(0,0) + I(1,1) < I(2,2)\n", index); + error_message("matrix is:\n" "[%.20e %.20e %.20e;\n" "%.20e %.20e %.20e;\n" "%.20e %.20e %.20e]\n", @@ -341,8 +341,8 @@ bool isValidInertiaMatrix(const mat33 &I, const int index, bool has_fixed_joint) return false; } if (I(1, 1) + I(2, 2) < I(0, 0)) { - bt_id_error_message("invalid inertia tensor for body %d, I(1,1) + I(2,2) < I(0,0)\n", index); - bt_id_error_message("matrix is:\n" + error_message("invalid inertia tensor for body %d, I(1,1) + I(2,2) < I(0,0)\n", index); + error_message("matrix is:\n" "[%.20e %.20e %.20e;\n" "%.20e %.20e %.20e;\n" "%.20e %.20e %.20e]\n", @@ -354,25 +354,25 @@ bool isValidInertiaMatrix(const mat33 &I, const int index, bool has_fixed_joint) // check positive/zero diagonal elements for (int i = 0; i < 3; i++) { if (I(i, i) < 0) { // accept zero - bt_id_error_message("invalid inertia tensor, I(%d,%d)= %e <0\n", i, i, I(i, i)); + error_message("invalid inertia tensor, I(%d,%d)= %e <0\n", i, i, I(i, i)); return false; } } // check symmetry if (BT_ID_FABS(I(1, 0) - I(0, 1)) > kIsZero) { - bt_id_error_message("invalid inertia tensor for body %d I(1,0)!=I(0,1). I(1,0)-I(0,1)= " + error_message("invalid inertia tensor for body %d I(1,0)!=I(0,1). I(1,0)-I(0,1)= " "%e\n", index, I(1, 0) - I(0, 1)); return false; } if (BT_ID_FABS(I(2, 0) - I(0, 2)) > kIsZero) { - bt_id_error_message("invalid inertia tensor for body %d I(2,0)!=I(0,2). I(2,0)-I(0,2)= " + error_message("invalid inertia tensor for body %d I(2,0)!=I(0,2). I(2,0)-I(0,2)= " "%e\n", index, I(2, 0) - I(0, 2)); return false; } if (BT_ID_FABS(I(1, 2) - I(2, 1)) > kIsZero) { - bt_id_error_message("invalid inertia tensor body %d I(1,2)!=I(2,1). I(1,2)-I(2,1)= %e\n", index, + error_message("invalid inertia tensor body %d I(1,2)!=I(2,1). I(1,2)-I(2,1)= %e\n", index, I(1, 2) - I(2, 1)); return false; } @@ -381,7 +381,7 @@ bool isValidInertiaMatrix(const mat33 &I, const int index, bool has_fixed_joint) bool isValidTransformMatrix(const mat33 &m) { #define print_mat(x) \ - bt_id_error_message("matrix is [%e, %e, %e; %e, %e, %e; %e, %e, %e]\n", x(0, 0), x(0, 1), x(0, 2), \ + error_message("matrix is [%e, %e, %e; %e, %e, %e; %e, %e, %e]\n", x(0, 0), x(0, 1), x(0, 2), \ x(1, 0), x(1, 1), x(1, 2), x(2, 0), x(2, 1), x(2, 2)) // check for unit length column vectors @@ -389,7 +389,7 @@ bool isValidTransformMatrix(const mat33 &m) { const idScalar length_minus_1 = BT_ID_FABS(m(0, i) * m(0, i) + m(1, i) * m(1, i) + m(2, i) * m(2, i) - 1.0); if (length_minus_1 > kAxisLengthEpsilon) { - bt_id_error_message("Not a valid rotation matrix (column %d not unit length)\n" + error_message("Not a valid rotation matrix (column %d not unit length)\n" "column = [%.18e %.18e %.18e]\n" "length-1.0= %.18e\n", i, m(0, i), m(1, i), m(2, i), length_minus_1); @@ -399,23 +399,23 @@ bool isValidTransformMatrix(const mat33 &m) { } // check for orthogonal column vectors if (BT_ID_FABS(m(0, 0) * m(0, 1) + m(1, 0) * m(1, 1) + m(2, 0) * m(2, 1)) > kAxisLengthEpsilon) { - bt_id_error_message("Not a valid rotation matrix (columns 0 and 1 not orthogonal)\n"); + error_message("Not a valid rotation matrix (columns 0 and 1 not orthogonal)\n"); print_mat(m); return false; } if (BT_ID_FABS(m(0, 0) * m(0, 2) + m(1, 0) * m(1, 2) + m(2, 0) * m(2, 2)) > kAxisLengthEpsilon) { - bt_id_error_message("Not a valid rotation matrix (columns 0 and 2 not orthogonal)\n"); + error_message("Not a valid rotation matrix (columns 0 and 2 not orthogonal)\n"); print_mat(m); return false; } if (BT_ID_FABS(m(0, 1) * m(0, 2) + m(1, 1) * m(1, 2) + m(2, 1) * m(2, 2)) > kAxisLengthEpsilon) { - bt_id_error_message("Not a valid rotation matrix (columns 0 and 2 not orthogonal)\n"); + error_message("Not a valid rotation matrix (columns 0 and 2 not orthogonal)\n"); print_mat(m); return false; } // check determinant (rotation not reflection) if (determinant(m) <= 0) { - bt_id_error_message("Not a valid rotation matrix (determinant <=0)\n"); + error_message("Not a valid rotation matrix (determinant <=0)\n"); print_mat(m); return false; } diff --git a/extern/bullet/src/BulletInverseDynamics/MultiBodyTree.cpp b/extern/bullet/src/BulletInverseDynamics/MultiBodyTree.cpp index becfe0f4a218..c67588d49fd5 100644 --- a/extern/bullet/src/BulletInverseDynamics/MultiBodyTree.cpp +++ b/extern/bullet/src/BulletInverseDynamics/MultiBodyTree.cpp @@ -83,11 +83,11 @@ int MultiBodyTree::numDoFs() const { return m_impl->m_num_dofs; } int MultiBodyTree::calculateInverseDynamics(const vecx &q, const vecx &u, const vecx &dot_u, vecx *joint_forces) { if (false == m_is_finalized) { - bt_id_error_message("system has not been initialized\n"); + error_message("system has not been initialized\n"); return -1; } if (-1 == m_impl->calculateInverseDynamics(q, u, dot_u, joint_forces)) { - bt_id_error_message("error in inverse dynamics calculation\n"); + error_message("error in inverse dynamics calculation\n"); return -1; } return 0; @@ -97,13 +97,13 @@ int MultiBodyTree::calculateMassMatrix(const vecx &q, const bool update_kinemati const bool initialize_matrix, const bool set_lower_triangular_matrix, matxx *mass_matrix) { if (false == m_is_finalized) { - bt_id_error_message("system has not been initialized\n"); + error_message("system has not been initialized\n"); return -1; } if (-1 == m_impl->calculateMassMatrix(q, update_kinematics, initialize_matrix, set_lower_triangular_matrix, mass_matrix)) { - bt_id_error_message("error in mass matrix calculation\n"); + error_message("error in mass matrix calculation\n"); return -1; } return 0; @@ -121,12 +121,12 @@ int MultiBodyTree::calculateKinematics(const vecx& q, const vecx& u, const vecx& setZero(m_impl->m_world_gravity); if (false == m_is_finalized) { - bt_id_error_message("system has not been initialized\n"); + error_message("system has not been initialized\n"); return -1; } if (-1 == m_impl->calculateKinematics(q, u, dot_u, MultiBodyTree::MultiBodyImpl::POSITION_VELOCITY_ACCELERATION)) { - bt_id_error_message("error in kinematics calculation\n"); + error_message("error in kinematics calculation\n"); return -1; } @@ -137,12 +137,12 @@ int MultiBodyTree::calculateKinematics(const vecx& q, const vecx& u, const vecx& int MultiBodyTree::calculatePositionKinematics(const vecx& q) { if (false == m_is_finalized) { - bt_id_error_message("system has not been initialized\n"); + error_message("system has not been initialized\n"); return -1; } if (-1 == m_impl->calculateKinematics(q, q, q, MultiBodyTree::MultiBodyImpl::POSITION_VELOCITY)) { - bt_id_error_message("error in kinematics calculation\n"); + error_message("error in kinematics calculation\n"); return -1; } return 0; @@ -150,12 +150,12 @@ int MultiBodyTree::calculatePositionKinematics(const vecx& q) { int MultiBodyTree::calculatePositionAndVelocityKinematics(const vecx& q, const vecx& u) { if (false == m_is_finalized) { - bt_id_error_message("system has not been initialized\n"); + error_message("system has not been initialized\n"); return -1; } if (-1 == m_impl->calculateKinematics(q, u, u, MultiBodyTree::MultiBodyImpl::POSITION_VELOCITY)) { - bt_id_error_message("error in kinematics calculation\n"); + error_message("error in kinematics calculation\n"); return -1; } return 0; @@ -165,12 +165,12 @@ int MultiBodyTree::calculatePositionAndVelocityKinematics(const vecx& q, const v #if (defined BT_ID_HAVE_MAT3X) && (defined BT_ID_WITH_JACOBIANS) int MultiBodyTree::calculateJacobians(const vecx& q, const vecx& u) { if (false == m_is_finalized) { - bt_id_error_message("system has not been initialized\n"); + error_message("system has not been initialized\n"); return -1; } if (-1 == m_impl->calculateJacobians(q, u, MultiBodyTree::MultiBodyImpl::POSITION_VELOCITY)) { - bt_id_error_message("error in jacobian calculation\n"); + error_message("error in jacobian calculation\n"); return -1; } return 0; @@ -178,12 +178,12 @@ int MultiBodyTree::calculateJacobians(const vecx& q, const vecx& u) { int MultiBodyTree::calculateJacobians(const vecx& q){ if (false == m_is_finalized) { - bt_id_error_message("system has not been initialized\n"); + error_message("system has not been initialized\n"); return -1; } if (-1 == m_impl->calculateJacobians(q, q, MultiBodyTree::MultiBodyImpl::POSITION_ONLY)) { - bt_id_error_message("error in jacobian calculation\n"); + error_message("error in jacobian calculation\n"); return -1; } return 0; @@ -214,7 +214,7 @@ int MultiBodyTree::addBody(int body_index, int parent_index, JointType joint_typ const vec3 &body_r_body_com, const mat33 &body_I_body, const int user_int, void *user_ptr) { if (body_index < 0) { - bt_id_error_message("body index must be positive (got %d)\n", body_index); + error_message("body index must be positive (got %d)\n", body_index); return -1; } vec3 body_axis_of_motion(body_axis_of_motion_); @@ -223,14 +223,14 @@ int MultiBodyTree::addBody(int body_index, int parent_index, JointType joint_typ case PRISMATIC: // check if axis is unit vector if (!isUnitVector(body_axis_of_motion)) { - bt_id_warning_message( + warning_message( "axis of motion not a unit axis ([%f %f %f]), will use normalized vector\n", body_axis_of_motion(0), body_axis_of_motion(1), body_axis_of_motion(2)); idScalar length = BT_ID_SQRT(BT_ID_POW(body_axis_of_motion(0), 2) + BT_ID_POW(body_axis_of_motion(1), 2) + BT_ID_POW(body_axis_of_motion(2), 2)); if (length < BT_ID_SQRT(std::numeric_limits::min())) { - bt_id_error_message("axis of motion vector too short (%e)\n", length); + error_message("axis of motion vector too short (%e)\n", length); return -1; } body_axis_of_motion = (1.0 / length) * body_axis_of_motion; @@ -241,14 +241,14 @@ int MultiBodyTree::addBody(int body_index, int parent_index, JointType joint_typ case FLOATING: break; default: - bt_id_error_message("unknown joint type %d\n", joint_type); + error_message("unknown joint type %d\n", joint_type); return -1; } // sanity check for mass properties. Zero mass is OK. if (mass < 0) { m_mass_parameters_are_valid = false; - bt_id_error_message("Body %d has invalid mass %e\n", body_index, mass); + error_message("Body %d has invalid mass %e\n", body_index, mass); if (!m_accept_invalid_mass_parameters) { return -1; } @@ -296,7 +296,7 @@ int MultiBodyTree::finalize() { const int &num_dofs = m_init_cache->numDoFs(); if(num_dofs<=0) { - bt_id_error_message("Need num_dofs>=1, but num_dofs= %d\n", num_dofs); + error_message("Need num_dofs>=1, but num_dofs= %d\n", num_dofs); //return -1; } @@ -331,22 +331,6 @@ int MultiBodyTree::finalize() { rigid_body.m_parent_pos_parent_body_ref = joint.m_parent_pos_parent_child_ref; rigid_body.m_joint_type = joint.m_type; - int user_int; - if (-1 == m_init_cache->getUserInt(index, &user_int)) { - return -1; - } - if (-1 == m_impl->setUserInt(index, user_int)) { - return -1; - } - - void* user_ptr; - if (-1 == m_init_cache->getUserPtr(index, &user_ptr)) { - return -1; - } - if (-1 == m_impl->setUserPtr(index, user_ptr)) { - return -1; - } - // Set joint Jacobians. Note that the dimension is always 3x1 here to avoid variable sized // matrices. switch (rigid_body.m_joint_type) { @@ -386,14 +370,14 @@ int MultiBodyTree::finalize() { rigid_body.m_Jac_JT(2) = 0.0; break; default: - bt_id_error_message("unsupported joint type %d\n", rigid_body.m_joint_type); + error_message("unsupported joint type %d\n", rigid_body.m_joint_type); return -1; } } // 4 assign degree of freedom indices & build per-joint-type index arrays if (-1 == m_impl->generateIndexSets()) { - bt_id_error_message("generating index sets\n"); + error_message("generating index sets\n"); return -1; } diff --git a/extern/bullet/src/BulletInverseDynamics/details/IDLinearMathInterface.hpp b/extern/bullet/src/BulletInverseDynamics/details/IDLinearMathInterface.hpp index c179daeec667..5bb4a33bdd46 100644 --- a/extern/bullet/src/BulletInverseDynamics/details/IDLinearMathInterface.hpp +++ b/extern/bullet/src/BulletInverseDynamics/details/IDLinearMathInterface.hpp @@ -49,9 +49,9 @@ inline mat33 operator*(const idScalar& s, const mat33& a) { return a * s; } class vecx : public btVectorX { public: - vecx(int size) : btVectorX(size) {} + vecx(int size) : btVectorX(size) {} const vecx& operator=(const btVectorX& rhs) { - *static_cast*>(this) = rhs; + *static_cast(this) = rhs; return *this; } @@ -78,7 +78,7 @@ inline vecx operator+(const vecx& a, const vecx& b) { vecx result(a.size()); // TODO: error handling for a.size() != b.size()?? if (a.size() != b.size()) { - bt_id_error_message("size missmatch. a.size()= %d, b.size()= %d\n", a.size(), b.size()); + error_message("size missmatch. a.size()= %d, b.size()= %d\n", a.size(), b.size()); abort(); } for (int i = 0; i < a.size(); i++) { @@ -92,7 +92,7 @@ inline vecx operator-(const vecx& a, const vecx& b) { vecx result(a.size()); // TODO: error handling for a.size() != b.size()?? if (a.size() != b.size()) { - bt_id_error_message("size missmatch. a.size()= %d, b.size()= %d\n", a.size(), b.size()); + error_message("size missmatch. a.size()= %d, b.size()= %d\n", a.size(), b.size()); abort(); } for (int i = 0; i < a.size(); i++) { @@ -121,7 +121,7 @@ class mat3x : public matxx { } void operator=(const mat3x& rhs) { if (m_cols != rhs.m_cols) { - bt_id_error_message("size missmatch, cols= %d but rhs.cols= %d\n", cols(), rhs.cols()); + error_message("size missmatch, cols= %d but rhs.cols= %d\n", cols(), rhs.cols()); abort(); } for(int i=0;i(m_parent_index.size())); } @@ -234,7 +234,7 @@ int MultiBodyTree::MultiBodyImpl::calculateInverseDynamics(const vecx &q, const const vecx &dot_u, vecx *joint_forces) { if (q.size() != m_num_dofs || u.size() != m_num_dofs || dot_u.size() != m_num_dofs || joint_forces->size() != m_num_dofs) { - bt_id_error_message("wrong vector dimension. system has %d DOFs,\n" + error_message("wrong vector dimension. system has %d DOFs,\n" "but dim(q)= %d, dim(u)= %d, dim(dot_u)= %d, dim(joint_forces)= %d\n", m_num_dofs, static_cast(q.size()), static_cast(u.size()), static_cast(dot_u.size()), static_cast(joint_forces->size())); @@ -242,7 +242,7 @@ int MultiBodyTree::MultiBodyImpl::calculateInverseDynamics(const vecx &q, const } // 1. relative kinematics if(-1 == calculateKinematics(q,u,dot_u, POSITION_VELOCITY_ACCELERATION)) { - bt_id_error_message("error in calculateKinematics\n"); + error_message("error in calculateKinematics\n"); return -1; } // 2. update contributions to equations of motion for every body. @@ -322,14 +322,14 @@ int MultiBodyTree::MultiBodyImpl::calculateInverseDynamics(const vecx &q, const int MultiBodyTree::MultiBodyImpl::calculateKinematics(const vecx &q, const vecx &u, const vecx& dot_u, const KinUpdateType type) { if (q.size() != m_num_dofs || u.size() != m_num_dofs || dot_u.size() != m_num_dofs ) { - bt_id_error_message("wrong vector dimension. system has %d DOFs,\n" + error_message("wrong vector dimension. system has %d DOFs,\n" "but dim(q)= %d, dim(u)= %d, dim(dot_u)= %d\n", m_num_dofs, static_cast(q.size()), static_cast(u.size()), static_cast(dot_u.size())); return -1; } if(type != POSITION_ONLY && type != POSITION_VELOCITY && type != POSITION_VELOCITY_ACCELERATION) { - bt_id_error_message("invalid type %d\n", type); + error_message("invalid type %d\n", type); return -1; } @@ -516,13 +516,13 @@ void MultiBodyTree::MultiBodyImpl::addRelativeJacobianComponent(RigidBody&body) int MultiBodyTree::MultiBodyImpl::calculateJacobians(const vecx& q, const vecx& u, const KinUpdateType type) { if (q.size() != m_num_dofs || u.size() != m_num_dofs) { - bt_id_error_message("wrong vector dimension. system has %d DOFs,\n" + error_message("wrong vector dimension. system has %d DOFs,\n" "but dim(q)= %d, dim(u)= %d\n", m_num_dofs, static_cast(q.size()), static_cast(u.size())); return -1; } if(type != POSITION_ONLY && type != POSITION_VELOCITY) { - bt_id_error_message("invalid type %d\n", type); + error_message("invalid type %d\n", type); return -1; } @@ -606,7 +606,7 @@ static inline int jointNumDoFs(const JointType &type) { return 6; } // this should never happen - bt_id_error_message("invalid joint type\n"); + error_message("invalid joint type\n"); // TODO add configurable abort/crash function abort(); return 0; @@ -626,7 +626,7 @@ int MultiBodyTree::MultiBodyImpl::calculateMassMatrix(const vecx &q, const bool if (q.size() != m_num_dofs || mass_matrix->rows() != m_num_dofs || mass_matrix->cols() != m_num_dofs) { - bt_id_error_message("Dimension error. System has %d DOFs,\n" + error_message("Dimension error. System has %d DOFs,\n" "but dim(q)= %d, dim(mass_matrix)= %d x %d\n", m_num_dofs, static_cast(q.size()), static_cast(mass_matrix->rows()), static_cast(mass_matrix->cols())); @@ -734,7 +734,7 @@ int MultiBodyTree::MultiBodyImpl::calculateMassMatrix(const vecx &q, const bool // 1. for multi-dof joints, rest of the dofs of this body for (int row = col - 1; row >= q_index_min; row--) { if (FLOATING != body.m_joint_type) { - bt_id_error_message("??\n"); + error_message("??\n"); return -1; } setSixDoFJacobians(row - q_index_min, Jac_JR, Jac_JT); @@ -788,7 +788,7 @@ int MultiBodyTree::MultiBodyImpl::calculateMassMatrix(const vecx &q, const bool #define CHECK_IF_BODY_INDEX_IS_VALID(index) \ do { \ if (index < 0 || index >= m_num_bodies) { \ - bt_id_error_message("invalid index %d (num_bodies= %d)\n", index, m_num_bodies); \ + error_message("invalid index %d (num_bodies= %d)\n", index, m_num_bodies); \ return -1; \ } \ } while (0) diff --git a/extern/bullet/src/BulletInverseDynamics/details/MultiBodyTreeInitCache.cpp b/extern/bullet/src/BulletInverseDynamics/details/MultiBodyTreeInitCache.cpp index e9511b70763e..47b4ab38908e 100644 --- a/extern/bullet/src/BulletInverseDynamics/details/MultiBodyTreeInitCache.cpp +++ b/extern/bullet/src/BulletInverseDynamics/details/MultiBodyTreeInitCache.cpp @@ -29,13 +29,13 @@ int MultiBodyTree::InitCache::addBody(const int body_index, const int parent_ind m_num_dofs += 6; break; default: - bt_id_error_message("unknown joint type %d\n", joint_type); + error_message("unknown joint type %d\n", joint_type); return -1; } if(-1 == parent_index) { if(m_root_index>=0) { - bt_id_error_message("trying to add body %d as root, but already added %d as root body\n", + error_message("trying to add body %d as root, but already added %d as root body\n", body_index, m_root_index); return -1; } @@ -63,7 +63,7 @@ int MultiBodyTree::InitCache::addBody(const int body_index, const int parent_ind } int MultiBodyTree::InitCache::getInertiaData(const int index, InertiaData* inertia) const { if (index < 0 || index > static_cast(m_inertias.size())) { - bt_id_error_message("index out of range\n"); + error_message("index out of range\n"); return -1; } @@ -73,7 +73,7 @@ int MultiBodyTree::InitCache::getInertiaData(const int index, InertiaData* inert int MultiBodyTree::InitCache::getUserInt(const int index, int* user_int) const { if (index < 0 || index > static_cast(m_user_int.size())) { - bt_id_error_message("index out of range\n"); + error_message("index out of range\n"); return -1; } *user_int = m_user_int[index]; @@ -82,7 +82,7 @@ int MultiBodyTree::InitCache::getUserInt(const int index, int* user_int) const { int MultiBodyTree::InitCache::getUserPtr(const int index, void** user_ptr) const { if (index < 0 || index > static_cast(m_user_ptr.size())) { - bt_id_error_message("index out of range\n"); + error_message("index out of range\n"); return -1; } *user_ptr = m_user_ptr[index]; @@ -91,7 +91,7 @@ int MultiBodyTree::InitCache::getUserPtr(const int index, void** user_ptr) const int MultiBodyTree::InitCache::getJointData(const int index, JointData* joint) const { if (index < 0 || index > static_cast(m_joints.size())) { - bt_id_error_message("index out of range\n"); + error_message("index out of range\n"); return -1; } *joint = m_joints[index]; diff --git a/extern/bullet/src/BulletInverseDynamics/premake4.lua b/extern/bullet/src/BulletInverseDynamics/premake4.lua index fdd176b09f78..774e037b3f44 100644 --- a/extern/bullet/src/BulletInverseDynamics/premake4.lua +++ b/extern/bullet/src/BulletInverseDynamics/premake4.lua @@ -1,9 +1,6 @@ project "BulletInverseDynamics" kind "StaticLib" - if os.is("Linux") then - buildoptions{"-fPIC"} - end includedirs { "..", } diff --git a/extern/bullet/src/BulletSoftBody/btSoftMultiBodyDynamicsWorld.cpp b/extern/bullet/src/BulletSoftBody/btSoftMultiBodyDynamicsWorld.cpp index 6facce4e8639..4e76dca9db10 100644 --- a/extern/bullet/src/BulletSoftBody/btSoftMultiBodyDynamicsWorld.cpp +++ b/extern/bullet/src/BulletSoftBody/btSoftMultiBodyDynamicsWorld.cpp @@ -157,7 +157,7 @@ void btSoftMultiBodyDynamicsWorld::removeCollisionObject(btCollisionObject* coll void btSoftMultiBodyDynamicsWorld::debugDrawWorld() { - btMultiBodyDynamicsWorld::debugDrawWorld(); + btDiscreteDynamicsWorld::debugDrawWorld(); if (getDebugDrawer()) { @@ -357,14 +357,10 @@ void btSoftMultiBodyDynamicsWorld::serialize(btSerializer* serializer) serializeSoftBodies(serializer); - serializeMultiBodies(serializer); - serializeRigidBodies(serializer); serializeCollisionObjects(serializer); - serializeContactManifolds(serializer); - serializer->finishSerialization(); } diff --git a/extern/bullet/src/BulletSoftBody/btSoftRigidDynamicsWorldMt.cpp b/extern/bullet/src/BulletSoftBody/btSoftRigidDynamicsWorldMt.cpp index 05301439ad01..bd3625a751cf 100644 --- a/extern/bullet/src/BulletSoftBody/btSoftRigidDynamicsWorldMt.cpp +++ b/extern/bullet/src/BulletSoftBody/btSoftRigidDynamicsWorldMt.cpp @@ -29,10 +29,9 @@ btSoftRigidDynamicsWorldMt::btSoftRigidDynamicsWorldMt( btDispatcher* dispatcher, btBroadphaseInterface* pairCache, btConstraintSolverPoolMt* constraintSolver, - btConstraintSolver* constraintSolverMt, btCollisionConfiguration* collisionConfiguration, btSoftBodySolver *softBodySolver ) : - btDiscreteDynamicsWorldMt(dispatcher,pairCache,constraintSolver,constraintSolverMt,collisionConfiguration), + btDiscreteDynamicsWorldMt(dispatcher,pairCache,constraintSolver,collisionConfiguration), m_softBodySolver( softBodySolver ), m_ownsSolver(false) { diff --git a/extern/bullet/src/BulletSoftBody/btSoftRigidDynamicsWorldMt.h b/extern/bullet/src/BulletSoftBody/btSoftRigidDynamicsWorldMt.h index 516fd3fe422d..be3b98c33615 100644 --- a/extern/bullet/src/BulletSoftBody/btSoftRigidDynamicsWorldMt.h +++ b/extern/bullet/src/BulletSoftBody/btSoftRigidDynamicsWorldMt.h @@ -13,8 +13,8 @@ subject to the following restrictions: 3. This notice may not be removed or altered from any source distribution. */ -#ifndef BT_SOFT_RIGID_DYNAMICS_WORLD_MT_H -#define BT_SOFT_RIGID_DYNAMICS_WORLD_MT_H +#ifndef BT_SOFT_RIGID_DYNAMICS_WORLD_H +#define BT_SOFT_RIGID_DYNAMICS_WORLD_H #include "BulletDynamics/Dynamics/btDiscreteDynamicsWorldMt.h" #include "btSoftBody.h" @@ -48,7 +48,7 @@ class btSoftRigidDynamicsWorldMt : public btDiscreteDynamicsWorldMt public: - btSoftRigidDynamicsWorldMt(btDispatcher* dispatcher,btBroadphaseInterface* pairCache,btConstraintSolverPoolMt* constraintSolver, btConstraintSolver* constraintSolverMt, btCollisionConfiguration* collisionConfiguration, btSoftBodySolver *softBodySolver = 0 ); + btSoftRigidDynamicsWorldMt(btDispatcher* dispatcher,btBroadphaseInterface* pairCache,btConstraintSolverPoolMt* constraintSolver, btCollisionConfiguration* collisionConfiguration, btSoftBodySolver *softBodySolver = 0 ); virtual ~btSoftRigidDynamicsWorldMt(); @@ -58,7 +58,7 @@ class btSoftRigidDynamicsWorldMt : public btDiscreteDynamicsWorldMt void removeSoftBody(btSoftBody* body); - ///removeCollisionObject will first check if it is a rigid body, if so call removeRigidBody otherwise call btDiscreteDynamicsWorldMt::removeCollisionObject + ///removeCollisionObject will first check if it is a rigid body, if so call removeRigidBody otherwise call btDiscreteDynamicsWorld::removeCollisionObject virtual void removeCollisionObject(btCollisionObject* collisionObject); int getDrawFlags() const { return(m_drawFlags); } @@ -104,4 +104,4 @@ class btSoftRigidDynamicsWorldMt : public btDiscreteDynamicsWorldMt }; -#endif //BT_SOFT_RIGID_DYNAMICS_WORLD_MT_H +#endif //BT_SOFT_RIGID_DYNAMICS_WORLD_H diff --git a/extern/bullet/src/BulletSoftBody/premake4.lua b/extern/bullet/src/BulletSoftBody/premake4.lua index a75e336194d9..57a575fb1831 100644 --- a/extern/bullet/src/BulletSoftBody/premake4.lua +++ b/extern/bullet/src/BulletSoftBody/premake4.lua @@ -5,9 +5,6 @@ includedirs { "..", } - if os.is("Linux") then - buildoptions{"-fPIC"} - end files { "**.cpp", "**.h" diff --git a/extern/bullet/src/Extras/BulletRobotics/CMakeLists.txt b/extern/bullet/src/Extras/BulletRobotics/CMakeLists.txt deleted file mode 100644 index ad37212a1f73..000000000000 --- a/extern/bullet/src/Extras/BulletRobotics/CMakeLists.txt +++ /dev/null @@ -1,197 +0,0 @@ - -INCLUDE_DIRECTORIES( - ${BULLET_PHYSICS_SOURCE_DIR}/src - ${BULLET_PHYSICS_SOURCE_DIR}/examples - ${BULLET_PHYSICS_SOURCE_DIR}/examples/SharedMemory - ${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs - ${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/enet/include - ${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/clsocket/src -) - -SET(BulletRobotics_SRCS - ../../examples/SharedMemory/plugins/collisionFilterPlugin/collisionFilterPlugin.cpp - ../../examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.cpp - ../../examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.h - ../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoGUI.cpp - ../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoGUI.h - ../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp - ../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.h - ../../examples/SharedMemory/IKTrajectoryHelper.cpp - ../../examples/SharedMemory/IKTrajectoryHelper.h - ../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp - ../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp - ../../examples/OpenGLWindow/SimpleCamera.cpp - ../../examples/OpenGLWindow/SimpleCamera.h - ../../examples/TinyRenderer/geometry.cpp - ../../examples/TinyRenderer/model.cpp - ../../examples/TinyRenderer/tgaimage.cpp - ../../examples/TinyRenderer/our_gl.cpp - ../../examples/TinyRenderer/TinyRenderer.cpp - ../../examples/SharedMemory/InProcessMemory.cpp - ../../examples/SharedMemory/PhysicsClient.cpp - ../../examples/SharedMemory/PhysicsClient.h - ../../examples/SharedMemory/PhysicsServer.cpp - ../../examples/SharedMemory/PhysicsServer.h - ../../examples/SharedMemory/PhysicsServerSharedMemory.cpp - ../../examples/SharedMemory/PhysicsServerSharedMemory.h - ../../examples/SharedMemory/PhysicsDirect.cpp - ../../examples/SharedMemory/PhysicsDirect.h - ../../examples/SharedMemory/PhysicsDirectC_API.cpp - ../../examples/SharedMemory/PhysicsDirectC_API.h - ../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp - ../../examples/SharedMemory/PhysicsServerCommandProcessor.h - ../../examples/SharedMemory/b3PluginManager.cpp - ../../examples/SharedMemory/b3PluginManager.h - - ../../examples/SharedMemory/PhysicsClientSharedMemory.cpp - ../../examples/SharedMemory/PhysicsClientSharedMemory.h - ../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp - ../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.h - ../../examples/SharedMemory/PhysicsClientC_API.cpp - - ../../examples/SharedMemory/PhysicsClientC_API.h - ../../examples/SharedMemory/SharedMemoryPublic.h - - ../../examples/SharedMemory/Win32SharedMemory.cpp - ../../examples/SharedMemory/Win32SharedMemory.h - ../../examples/SharedMemory/PosixSharedMemory.cpp - ../../examples/SharedMemory/PosixSharedMemory.h - - ../../examples/Utils/b3ResourcePath.cpp - ../../examples/Utils/b3ResourcePath.h - ../../examples/Utils/RobotLoggingUtil.cpp - ../../examples/Utils/RobotLoggingUtil.h - ../../examples/Utils/b3Clock.cpp - ../../examples/Utils/b3ResourcePath.cpp - ../../examples/Utils/b3ERPCFMHelper.hpp - ../../examples/Utils/b3ReferenceFrameHelper.hpp - ../../examples/Utils/ChromeTraceUtil.cpp - - ../../examples/ThirdPartyLibs/tinyxml2/tinyxml2.cpp - - ../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp - ../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.h - - ../../examples/ThirdPartyLibs/stb_image/stb_image.cpp - - ../../examples/ThirdPartyLibs/BussIK/Jacobian.cpp - ../../examples/ThirdPartyLibs/BussIK/LinearR2.cpp - ../../examples/ThirdPartyLibs/BussIK/LinearR3.cpp - ../../examples/ThirdPartyLibs/BussIK/LinearR4.cpp - ../../examples/ThirdPartyLibs/BussIK/MatrixRmn.cpp - ../../examples/ThirdPartyLibs/BussIK/Misc.cpp - ../../examples/ThirdPartyLibs/BussIK/Node.cpp - ../../examples/ThirdPartyLibs/BussIK/Tree.cpp - ../../examples/ThirdPartyLibs/BussIK/VectorRn.cpp - - ../../examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp - ../../examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp - ../../examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp - ../../examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp - ../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp - ../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp - ../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp - ../../examples/Importers/ImportURDFDemo/UrdfParser.cpp - ../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp - ../../examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp - - ../../examples/MultiThreading/b3PosixThreadSupport.cpp - ../../examples/MultiThreading/b3Win32ThreadSupport.cpp - ../../examples/MultiThreading/b3ThreadSupportInterface.cpp -) - -IF(BUILD_CLSOCKET) - ADD_DEFINITIONS(-DBT_ENABLE_CLSOCKET) -ENDIF(BUILD_CLSOCKET) - -IF(WIN32) - IF(BUILD_ENET) - ADD_DEFINITIONS(-DWIN32 -DBT_ENABLE_ENET) - ENDIF(BUILD_ENET) - IF(BUILD_CLSOCKET) - ADD_DEFINITIONS(-DWIN32) - ENDIF(BUILD_CLSOCKET) - -ELSE(WIN32) - IF(BUILD_ENET) - ADD_DEFINITIONS(-DHAS_SOCKLEN_T -DBT_ENABLE_ENET) - ENDIF(BUILD_ENET) - - IF(BUILD_CLSOCKET) - ADD_DEFINITIONS(${OSDEF}) - ENDIF(BUILD_CLSOCKET) - - IF(NOT APPLE) - LINK_LIBRARIES( pthread ${DL} ) - ENDIF(NOT APPLE) -ENDIF(WIN32) - -IF(BUILD_ENET) - set(BulletRobotics_SRCS ${BulletRobotics_SRCS} - ../../examples/SharedMemory/PhysicsClientUDP.cpp - ../../examples/SharedMemory/PhysicsClientUDP_C_API.cpp - ../../examples/SharedMemory/PhysicsClientUDP.h - ../../examples/SharedMemory/PhysicsClientUDP_C_API.h - ../../examples/ThirdPartyLibs/enet/win32.c - ../../examples/ThirdPartyLibs/enet/unix.c - ../../examples/ThirdPartyLibs/enet/callbacks.c - ../../examples/ThirdPartyLibs/enet/compress.c - ../../examples/ThirdPartyLibs/enet/host.c - ../../examples/ThirdPartyLibs/enet/list.c - ../../examples/ThirdPartyLibs/enet/packet.c - ../../examples/ThirdPartyLibs/enet/peer.c - ../../examples/ThirdPartyLibs/enet/protocol.c - ) - -ENDIF(BUILD_ENET) - -IF(BUILD_CLSOCKET) - set(BulletRobotics_SRCS ${BulletRobotics_SRCS} - ../../examples/SharedMemory/PhysicsClientTCP.cpp - ../../examples/SharedMemory/PhysicsClientTCP.h - ../../examples/SharedMemory/PhysicsClientTCP_C_API.cpp - ../../examples/SharedMemory/PhysicsClientTCP_C_API.h - ../../examples/ThirdPartyLibs/clsocket/src/SimpleSocket.cpp - ../../examples/ThirdPartyLibs/clsocket/src/ActiveSocket.cpp - ../../examples/ThirdPartyLibs/clsocket/src/PassiveSocket.cpp - ) -ENDIF() - -ADD_DEFINITIONS(-DPHYSICS_SERVER_DIRECT) - - -ADD_LIBRARY(BulletRobotics ${BulletRobotics_SRCS}) - -SET_TARGET_PROPERTIES(BulletRobotics PROPERTIES VERSION ${BULLET_VERSION}) -SET_TARGET_PROPERTIES(BulletRobotics PROPERTIES SOVERSION ${BULLET_VERSION}) - -IF (BUILD_SHARED_LIBS) - TARGET_LINK_LIBRARIES(BulletRobotics BulletInverseDynamicsUtils BulletWorldImporter BulletFileLoader BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamics LinearMath Bullet3Common) -ENDIF (BUILD_SHARED_LIBS) - -IF (INSTALL_EXTRA_LIBS) - INSTALL(FILES - ../../examples/SharedMemory/PhysicsClientC_API.h - ../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.h - ../../examples/SharedMemory/PhysicsClientSharedMemory2_C_API.h - ../../examples/SharedMemory/PhysicsDirectC_API.h - ../../examples/SharedMemory/PhysicsClientUDP_C_API.h - ../../examples/SharedMemory/PhysicsClientTCP_C_API.h - ../../examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.h - ../../examples/SharedMemory/SharedMemoryPublic.h - ../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoGUI.h - ../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.h - DESTINATION include/bullet - ) - INSTALL(TARGETS - BulletRobotics - LIBRARY DESTINATION lib${LIB_SUFFIX} - ARCHIVE DESTINATION lib${LIB_SUFFIX} - ) - - IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - SET_TARGET_PROPERTIES(BulletRobotics PROPERTIES FRAMEWORK true) - SET_TARGET_PROPERTIES(BulletRobotics PROPERTIES PUBLIC_HEADER "PhysicsClientC_API.h" ) - ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - -ENDIF (INSTALL_EXTRA_LIBS) diff --git a/extern/bullet/src/Extras/BulletRobotics/premake4.lua b/extern/bullet/src/Extras/BulletRobotics/premake4.lua deleted file mode 100644 index deb4a869ae76..000000000000 --- a/extern/bullet/src/Extras/BulletRobotics/premake4.lua +++ /dev/null @@ -1,180 +0,0 @@ - - -project ("BulletRobotics") - language "C++" - kind "StaticLib" - - includedirs {"../../src", "../../examples", - "../../examples/ThirdPartyLibs"} - defines {"PHYSICS_IN_PROCESS_EXAMPLE_BROWSER"} - hasCL = findOpenCL("clew") - - links{"BulletExampleBrowserLib","gwen", "BulletFileLoader","BulletWorldImporter","OpenGL_Window","BulletSoftBody", "BulletInverseDynamicsUtils", "BulletInverseDynamics", "BulletDynamics","BulletCollision","LinearMath","BussIK", "Bullet3Common"} - initOpenGL() - initGlew() - - includedirs { - "../../src", - "../../examples", - "../../examples/SharedMemory", - "../ThirdPartyLibs", - "../ThirdPartyLibs/enet/include", - "../ThirdPartyLibs/clsocket/src", - } - - if os.is("MacOSX") then --- targetextension {"so"} - links{"Cocoa.framework","Python"} - end - - -if not _OPTIONS["no-enet"] then - - includedirs {"../../examples/ThirdPartyLibs/enet/include"} - - if os.is("Windows") then --- targetextension {"dylib"} - defines { "WIN32" } - links {"Ws2_32","Winmm"} - end - if os.is("Linux") then - end - if os.is("MacOSX") then - end - - links {"enet"} - - files { - "../../examples/SharedMemory/PhysicsClientUDP.cpp", - "../../examples/SharedMemory/PhysicsClientUDP.h", - "../../examples/SharedMemory/PhysicsClientUDP_C_API.cpp", - "../../examples/SharedMemory/PhysicsClientUDP_C_API.h", - } - defines {"BT_ENABLE_ENET"} - end - - if not _OPTIONS["no-clsocket"] then - - includedirs {"../../examples/ThirdPartyLibs/clsocket/src"} - - if os.is("Windows") then - defines { "WIN32" } - links {"Ws2_32","Winmm"} - end - if os.is("Linux") then - defines {"_LINUX"} - end - if os.is("MacOSX") then - defines {"_DARWIN"} - end - - links {"clsocket"} - - files { - "../../examples/SharedMemory/PhysicsClientTCP.cpp", - "../../examples/SharedMemory/PhysicsClientTCP.h", - "../../examples/SharedMemory/PhysicsClientTCP_C_API.cpp", - "../../examples/SharedMemory/PhysicsClientTCP_C_API.h", - } - defines {"BT_ENABLE_CLSOCKET"} - end - - - files { - "../../examples/SharedMemory/plugins/collisionFilterPlugin/collisionFilterPlugin.cpp", - "../../examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.cpp", - "../../examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.h", - "../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoGUI.cpp", - "../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoGUI.h", - "../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp", - "../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.h", - "../../examples/SharedMemory/IKTrajectoryHelper.cpp", - "../../examples/SharedMemory/IKTrajectoryHelper.h", - "../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp", - "../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp", - "../../examples/OpenGLWindow/SimpleCamera.cpp", - "../../examples/OpenGLWindow/SimpleCamera.h", - "../../examples/TinyRenderer/geometry.cpp", - "../../examples/TinyRenderer/model.cpp", - "../../examples/TinyRenderer/tgaimage.cpp", - "../../examples/TinyRenderer/our_gl.cpp", - "../../examples/TinyRenderer/TinyRenderer.cpp", - "../../examples/SharedMemory/InProcessMemory.cpp", - "../../examples/SharedMemory/PhysicsClient.cpp", - "../../examples/SharedMemory/PhysicsClient.h", - "../../examples/SharedMemory/PhysicsServer.cpp", - "../../examples/SharedMemory/PhysicsServer.h", - "../../examples/SharedMemory/PhysicsServerSharedMemory.cpp", - "../../examples/SharedMemory/PhysicsServerSharedMemory.h", - "../../examples/SharedMemory/PhysicsDirect.cpp", - "../../examples/SharedMemory/PhysicsDirect.h", - "../../examples/SharedMemory/PhysicsDirectC_API.cpp", - "../../examples/SharedMemory/PhysicsDirectC_API.h", - "../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp", - "../../examples/SharedMemory/PhysicsServerCommandProcessor.h", - "../../examples/SharedMemory/b3PluginManager.cpp", - "../../examples/SharedMemory/b3PluginManager.h", - - "../../examples/SharedMemory/PhysicsClientSharedMemory.cpp", - "../../examples/SharedMemory/PhysicsClientSharedMemory.h", - "../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp", - "../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.h", - "../../examples/SharedMemory/PhysicsClientC_API.cpp", - - "../../examples/SharedMemory/PhysicsClientC_API.h", - "../../examples/SharedMemory/SharedMemoryPublic.h", - - "../../examples/SharedMemory/Win32SharedMemory.cpp", - "../../examples/SharedMemory/Win32SharedMemory.h", - "../../examples/SharedMemory/PosixSharedMemory.cpp", - "../../examples/SharedMemory/PosixSharedMemory.h", - - "../../examples/Utils/b3ResourcePath.cpp", - "../../examples/Utils/b3ResourcePath.h", - "../../examples/Utils/RobotLoggingUtil.cpp", - "../../examples/Utils/RobotLoggingUtil.h", - "../../examples/Utils/b3Clock.cpp", - "../../examples/Utils/b3ResourcePath.cpp", - "../../examples/Utils/b3ERPCFMHelper.hpp", - "../../examples/Utils/b3ReferenceFrameHelper.hpp", - "../../examples/Utils/ChromeTraceUtil.cpp", - - "../../examples/ThirdPartyLibs/tinyxml2/tinyxml2.cpp", - - "../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp", - "../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.h", - - "../../examples/ThirdPartyLibs/stb_image/stb_image.cpp", - - "../../examples/ThirdPartyLibs/BussIK/Jacobian.cpp", - "../../examples/ThirdPartyLibs/BussIK/LinearR2.cpp", - "../../examples/ThirdPartyLibs/BussIK/LinearR3.cpp", - "../../examples/ThirdPartyLibs/BussIK/LinearR4.cpp", - "../../examples/ThirdPartyLibs/BussIK/MatrixRmn.cpp", - "../../examples/ThirdPartyLibs/BussIK/Misc.cpp", - "../../examples/ThirdPartyLibs/BussIK/Node.cpp", - "../../examples/ThirdPartyLibs/BussIK/Tree.cpp", - "../../examples/ThirdPartyLibs/BussIK/VectorRn.cpp", - - "../../examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp", - "../../examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp", - "../../examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp", - "../../examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp", - "../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp", - "../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp", - "../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp", - "../../examples/Importers/ImportURDFDemo/UrdfParser.cpp", - "../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp", - "../../examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp", - - "../../examples/MultiThreading/b3PosixThreadSupport.cpp", - "../../examples/MultiThreading/b3Win32ThreadSupport.cpp", - "../../examples/MultiThreading/b3ThreadSupportInterface.cpp", - } - -if (_OPTIONS["enable_static_vr_plugin"]) then - files {"../../examples/SharedMemory/plugins/vrSyncPlugin/vrSyncPlugin.cpp"} -end - - - diff --git a/extern/bullet/src/Extras/CMakeLists.txt b/extern/bullet/src/Extras/CMakeLists.txt deleted file mode 100644 index 6b35357a3afd..000000000000 --- a/extern/bullet/src/Extras/CMakeLists.txt +++ /dev/null @@ -1,9 +0,0 @@ -SUBDIRS( InverseDynamics BulletRobotics obj2sdf Serialize ConvexDecomposition HACD GIMPACTUtils ) - - - -#Maya Dynamica plugin is moved to http://dynamica.googlecode.com - -#IF (USE_GLUT AND GLUT_FOUND) -# SUBDIRS (glui) -#ENDIF () diff --git a/extern/bullet/src/Extras/ConvexDecomposition/CMakeLists.txt b/extern/bullet/src/Extras/ConvexDecomposition/CMakeLists.txt deleted file mode 100644 index 132a336fad74..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/CMakeLists.txt +++ /dev/null @@ -1,67 +0,0 @@ -INCLUDE_DIRECTORIES( - ${BULLET_PHYSICS_SOURCE_DIR}/Extras/ConvexDecomposition ${BULLET_PHYSICS_SOURCE_DIR}/src -) - -SET(ConvexDecomposition_SRCS - bestfitobb.cpp - ConvexBuilder.cpp - cd_wavefront.cpp - fitsphere.cpp - meshvolume.cpp - raytri.cpp - vlookup.cpp - bestfit.cpp - cd_hull.cpp - ConvexDecomposition.cpp - concavity.cpp - float_math.cpp - planetri.cpp - splitplane.cpp -) - -SET(ConvexDecomposition_HDRS - ConvexDecomposition.h - cd_vector.h - concavity.h - bestfitobb.h - ConvexBuilder.h - cd_wavefront.h - fitsphere.h - meshvolume.h - raytri.h - vlookup.h - bestfit.h - cd_hull.h -) - -ADD_LIBRARY(ConvexDecomposition ${ConvexDecomposition_SRCS} ${ConvexDecomposition_HDRS}) -SET_TARGET_PROPERTIES(ConvexDecomposition PROPERTIES VERSION ${BULLET_VERSION}) -SET_TARGET_PROPERTIES(ConvexDecomposition PROPERTIES SOVERSION ${BULLET_VERSION}) - -IF (BUILD_SHARED_LIBS) - TARGET_LINK_LIBRARIES(ConvexDecomposition BulletCollision LinearMath) -ENDIF (BUILD_SHARED_LIBS) - -IF (INSTALL_EXTRA_LIBS) - IF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES) - #FILES_MATCHING requires CMake 2.6 - IF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5) - IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - INSTALL(TARGETS ConvexDecomposition DESTINATION .) - ELSE (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - INSTALL(TARGETS ConvexDecomposition - RUNTIME DESTINATION bin - LIBRARY DESTINATION lib${LIB_SUFFIX} - ARCHIVE DESTINATION lib${LIB_SUFFIX}) - INSTALL(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} -DESTINATION ${INCLUDE_INSTALL_DIR} FILES_MATCHING PATTERN "*.h" PATTERN -".svn" EXCLUDE PATTERN "CMakeFiles" EXCLUDE) - ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - ENDIF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5) - - IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - SET_TARGET_PROPERTIES(ConvexDecomposition PROPERTIES FRAMEWORK true) - SET_TARGET_PROPERTIES(ConvexDecomposition PROPERTIES PUBLIC_HEADER "${ConvexDecomposition_HDRS}") - ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - ENDIF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES) -ENDIF (INSTALL_EXTRA_LIBS) diff --git a/extern/bullet/src/Extras/ConvexDecomposition/ConvexBuilder.cpp b/extern/bullet/src/Extras/ConvexDecomposition/ConvexBuilder.cpp deleted file mode 100644 index e6f5ee61ccab..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/ConvexBuilder.cpp +++ /dev/null @@ -1,373 +0,0 @@ -#include "float_math.h" -#include "ConvexBuilder.h" -#include "meshvolume.h" -#include "bestfit.h" -#include -#include "cd_hull.h" - -#include "fitsphere.h" -#include "bestfitobb.h" - -unsigned int MAXDEPTH = 8 ; -float CONCAVE_PERCENT = 1.0f ; -float MERGE_PERCENT = 2.0f ; - -CHull::CHull(const ConvexDecomposition::ConvexResult &result) -{ - mResult = new ConvexDecomposition::ConvexResult(result); - mVolume = computeMeshVolume( result.mHullVertices, result.mHullTcount, result.mHullIndices ); - - mDiagonal = getBoundingRegion( result.mHullVcount, result.mHullVertices, sizeof(float)*3, mMin, mMax ); - - float dx = mMax[0] - mMin[0]; - float dy = mMax[1] - mMin[1]; - float dz = mMax[2] - mMin[2]; - - dx*=0.1f; // inflate 1/10th on each edge - dy*=0.1f; // inflate 1/10th on each edge - dz*=0.1f; // inflate 1/10th on each edge - - mMin[0]-=dx; - mMin[1]-=dy; - mMin[2]-=dz; - - mMax[0]+=dx; - mMax[1]+=dy; - mMax[2]+=dz; - - -} - -CHull::~CHull(void) -{ - delete mResult; -} - -bool CHull::overlap(const CHull &h) const -{ - return overlapAABB(mMin,mMax, h.mMin, h.mMax ); -} - - - - -ConvexBuilder::ConvexBuilder(ConvexDecompInterface *callback) -{ - mCallback = callback; -} - -ConvexBuilder::~ConvexBuilder(void) -{ - int i; - for (i=0;ioverlap(*b) ) return 0; // if their AABB's (with a little slop) don't overlap, then return. - - CHull *ret = 0; - - // ok..we are going to combine both meshes into a single mesh - // and then we are going to compute the concavity... - - VertexLookup vc = Vl_createVertexLookup(); - - UintVector indices; - - getMesh( *a->mResult, vc, indices ); - getMesh( *b->mResult, vc, indices ); - - unsigned int vcount = Vl_getVcount(vc); - const float *vertices = Vl_getVertices(vc); - unsigned int tcount = indices.size()/3; - - //don't do anything if hull is empty - if (!tcount) - { - Vl_releaseVertexLookup (vc); - return 0; - } - - ConvexDecomposition::HullResult hresult; - ConvexDecomposition::HullLibrary hl; - ConvexDecomposition::HullDesc desc; - - desc.SetHullFlag(ConvexDecomposition::QF_TRIANGLES); - - desc.mVcount = vcount; - desc.mVertices = vertices; - desc.mVertexStride = sizeof(float)*3; - - ConvexDecomposition::HullError hret = hl.CreateConvexHull(desc,hresult); - - if ( hret == ConvexDecomposition::QE_OK ) - { - - float combineVolume = computeMeshVolume( hresult.mOutputVertices, hresult.mNumFaces, hresult.mIndices ); - float sumVolume = a->mVolume + b->mVolume; - - float percent = (sumVolume*100) / combineVolume; - if ( percent >= (100.0f-MERGE_PERCENT) ) - { - ConvexDecomposition::ConvexResult cr(hresult.mNumOutputVertices, hresult.mOutputVertices, hresult.mNumFaces, hresult.mIndices); - ret = new CHull(cr); - } - } - - - Vl_releaseVertexLookup(vc); - - return ret; -} - -bool ConvexBuilder::combineHulls(void) -{ - - bool combine = false; - - sortChulls(mChulls); // sort the convex hulls, largest volume to least... - - CHullVector output; // the output hulls... - - - int i; - - for (i=0;imResult; // the high resolution hull... - - ConvexDecomposition::HullResult result; - ConvexDecomposition::HullLibrary hl; - ConvexDecomposition::HullDesc hdesc; - - hdesc.SetHullFlag(ConvexDecomposition::QF_TRIANGLES); - - hdesc.mVcount = c.mHullVcount; - hdesc.mVertices = c.mHullVertices; - hdesc.mVertexStride = sizeof(float)*3; - hdesc.mMaxVertices = desc.mMaxVertices; // maximum number of vertices allowed in the output - - if ( desc.mSkinWidth ) - { - hdesc.mSkinWidth = desc.mSkinWidth; - hdesc.SetHullFlag(ConvexDecomposition::QF_SKIN_WIDTH); // do skin width computation. - } - - ConvexDecomposition::HullError ret = hl.CreateConvexHull(hdesc,result); - - if ( ret == ConvexDecomposition::QE_OK ) - { - ConvexDecomposition::ConvexResult r(result.mNumOutputVertices, result.mOutputVertices, result.mNumFaces, result.mIndices); - - r.mHullVolume = computeMeshVolume( result.mOutputVertices, result.mNumFaces, result.mIndices ); // the volume of the hull. - - // compute the best fit OBB - computeBestFitOBB( result.mNumOutputVertices, result.mOutputVertices, sizeof(float)*3, r.mOBBSides, r.mOBBTransform ); - - r.mOBBVolume = r.mOBBSides[0] * r.mOBBSides[1] *r.mOBBSides[2]; // compute the OBB volume. - - fm_getTranslation( r.mOBBTransform, r.mOBBCenter ); // get the translation component of the 4x4 matrix. - - fm_matrixToQuat( r.mOBBTransform, r.mOBBOrientation ); // extract the orientation as a quaternion. - - r.mSphereRadius = computeBoundingSphere( result.mNumOutputVertices, result.mOutputVertices, r.mSphereCenter ); - r.mSphereVolume = fm_sphereVolume( r.mSphereRadius ); - - - mCallback->ConvexDecompResult(r); - } - - hl.ReleaseResult (result); - - - delete cr; - } - - ret = mChulls.size(); - - mChulls.clear(); - - return ret; -} - - -void ConvexBuilder::ConvexDebugTri(const float *p1,const float *p2,const float *p3,unsigned int color) -{ - mCallback->ConvexDebugTri(p1,p2,p3,color); -} - -void ConvexBuilder::ConvexDebugOBB(const float *sides, const float *matrix,unsigned int color) -{ - mCallback->ConvexDebugOBB(sides,matrix,color); -} -void ConvexBuilder::ConvexDebugPoint(const float *p,float dist,unsigned int color) -{ - mCallback->ConvexDebugPoint(p,dist,color); -} - -void ConvexBuilder::ConvexDebugBound(const float *bmin,const float *bmax,unsigned int color) -{ - mCallback->ConvexDebugBound(bmin,bmax,color); -} - -void ConvexBuilder::ConvexDecompResult(ConvexDecomposition::ConvexResult &result) -{ - CHull *ch = new CHull(result); - mChulls.push_back(ch); -} - -void ConvexBuilder::sortChulls(CHullVector &hulls) -{ - hulls.quickSort(CHullSort()); - //hulls.heapSort(CHullSort()); -} - - diff --git a/extern/bullet/src/Extras/ConvexDecomposition/ConvexBuilder.h b/extern/bullet/src/Extras/ConvexDecomposition/ConvexBuilder.h deleted file mode 100644 index 38eb9d41dfbc..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/ConvexBuilder.h +++ /dev/null @@ -1,110 +0,0 @@ -#ifndef CONVEX_BUILDER_H -#define CONVEX_BUILDER_H - -/*---------------------------------------------------------------------- -Copyright (c) 2004 Open Dynamics Framework Group -www.physicstools.org -All rights reserved. - -Redistribution and use in source and binary forms, with or without modification, are permitted provided -that the following conditions are met: - -Redistributions of source code must retain the above copyright notice, this list of conditions -and the following disclaimer. - -Redistributions in binary form must reproduce the above copyright notice, -this list of conditions and the following disclaimer in the documentation -and/or other materials provided with the distribution. - -Neither the name of the Open Dynamics Framework Group nor the names of its contributors may -be used to endorse or promote products derived from this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, -INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, -EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER -IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF -THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -// http://codesuppository.blogspot.com -// -// mailto: jratcliff@infiniplex.net -// -// http://www.amillionpixels.us -// - - -#include "ConvexDecomposition.h" -#include "vlookup.h" -#include "LinearMath/btAlignedObjectArray.h" - - -class CHull -{ -public: - CHull(const ConvexDecomposition::ConvexResult &result); - - ~CHull(void); - - bool overlap(const CHull &h) const; - - float mMin[3]; - float mMax[3]; - float mVolume; - float mDiagonal; // long edge.. - ConvexDecomposition::ConvexResult *mResult; -}; - -// Usage: std::sort( list.begin(), list.end(), StringSortRef() ); -class CHullSort -{ -public: - - inline bool operator()(const CHull *a,const CHull *b) const - { - return a->mVolume < b->mVolume; - } -}; - - -typedef btAlignedObjectArray< CHull * > CHullVector; - - - -class ConvexBuilder : public ConvexDecomposition::ConvexDecompInterface -{ -public: - ConvexBuilder(ConvexDecomposition::ConvexDecompInterface *callback); - - virtual ~ConvexBuilder(void); - - bool isDuplicate(unsigned int i1,unsigned int i2,unsigned int i3, - unsigned int ci1,unsigned int ci2,unsigned int ci3); - - void getMesh(const ConvexDecomposition::ConvexResult &cr,VertexLookup vc,UintVector &indices); - - CHull * canMerge(CHull *a,CHull *b); - - bool combineHulls(void); - - unsigned int process(const ConvexDecomposition::DecompDesc &desc); - - virtual void ConvexDebugTri(const float *p1,const float *p2,const float *p3,unsigned int color); - - virtual void ConvexDebugOBB(const float *sides, const float *matrix,unsigned int color); - virtual void ConvexDebugPoint(const float *p,float dist,unsigned int color); - - virtual void ConvexDebugBound(const float *bmin,const float *bmax,unsigned int color); - - virtual void ConvexDecompResult(ConvexDecomposition::ConvexResult &result); - - void sortChulls(CHullVector &hulls); - - CHullVector mChulls; - ConvexDecompInterface *mCallback; -}; - -#endif //CONVEX_BUILDER_H - diff --git a/extern/bullet/src/Extras/ConvexDecomposition/ConvexDecomposition.cpp b/extern/bullet/src/Extras/ConvexDecomposition/ConvexDecomposition.cpp deleted file mode 100644 index 572d25f5bff5..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/ConvexDecomposition.cpp +++ /dev/null @@ -1,375 +0,0 @@ -#include "float_math.h" - -#include -#include -#include -#include - - -/*---------------------------------------------------------------------- - Copyright (c) 2004 Open Dynamics Framework Group - www.physicstools.org - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are permitted provided - that the following conditions are met: - - Redistributions of source code must retain the above copyright notice, this list of conditions - and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - Neither the name of the Open Dynamics Framework Group nor the names of its contributors may - be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER - IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -// http://codesuppository.blogspot.com -// -// mailto: jratcliff@infiniplex.net -// -// http://www.amillionpixels.us -// - -#include "ConvexDecomposition.h" -#include "cd_vector.h" -#include "cd_hull.h" -#include "bestfit.h" -#include "planetri.h" -#include "vlookup.h" -#include "splitplane.h" -#include "meshvolume.h" -#include "concavity.h" -#include "bestfitobb.h" -#include "float_math.h" -#include "fitsphere.h" - -#define SHOW_MESH 0 -#define MAKE_MESH 1 - - -using namespace ConvexDecomposition; - - - -namespace ConvexDecomposition -{ - -class FaceTri -{ -public: - FaceTri(void) { }; - FaceTri(const float *vertices,unsigned int i1,unsigned int i2,unsigned int i3) - { - mP1.Set( &vertices[i1*3] ); - mP2.Set( &vertices[i2*3] ); - mP3.Set( &vertices[i3*3] ); - } - - Vector3d mP1; - Vector3d mP2; - Vector3d mP3; - Vector3d mNormal; - -}; - - -void addTri(VertexLookup vl,UintVector &list,const Vector3d &p1,const Vector3d &p2,const Vector3d &p3) -{ - unsigned int i1 = Vl_getIndex(vl, p1.Ptr() ); - unsigned int i2 = Vl_getIndex(vl, p2.Ptr() ); - unsigned int i3 = Vl_getIndex(vl, p3.Ptr() ); - - // do *not* process degenerate triangles! - - if ( i1 != i2 && i1 != i3 && i2 != i3 ) - { - list.push_back(i1); - list.push_back(i2); - list.push_back(i3); - } -} - - -void calcConvexDecomposition(unsigned int vcount, - const float *vertices, - unsigned int tcount, - const unsigned int *indices, - ConvexDecompInterface *callback, - float masterVolume, - unsigned int depth) - -{ - - float plane[4]; - - bool split = false; - - - if ( depth < MAXDEPTH ) - { - - float volume; - float c = computeConcavity( vcount, vertices, tcount, indices, callback, plane, volume ); - - if ( depth == 0 ) - { - masterVolume = volume; - } - - float percent = (c*100.0f)/masterVolume; - - if ( percent > CONCAVE_PERCENT ) // if great than 5% of the total volume is concave, go ahead and keep splitting. - { - split = true; - } - - } - - if ( depth >= MAXDEPTH || !split ) - { - -#if 1 - - HullResult result; - HullLibrary hl; - HullDesc desc; - - desc.SetHullFlag(QF_TRIANGLES); - - desc.mVcount = vcount; - desc.mVertices = vertices; - desc.mVertexStride = sizeof(float)*3; - - HullError ret = hl.CreateConvexHull(desc,result); - - if ( ret == QE_OK ) - { - - ConvexResult r(result.mNumOutputVertices, result.mOutputVertices, result.mNumFaces, result.mIndices); - - - callback->ConvexDecompResult(r); - } - - -#else - - static unsigned int colors[8] = - { - 0xFF0000, - 0x00FF00, - 0x0000FF, - 0xFFFF00, - 0x00FFFF, - 0xFF00FF, - 0xFFFFFF, - 0xFF8040 - }; - - static int count = 0; - - count++; - - if ( count == 8 ) count = 0; - - assert( count >= 0 && count < 8 ); - - unsigned int color = colors[count]; - - const unsigned int *source = indices; - - for (unsigned int i=0; iConvexDebugTri( t.mP1.Ptr(), t.mP2.Ptr(), t.mP3.Ptr(), color ); - - } -#endif - - hl.ReleaseResult (result); - return; - - } - - UintVector ifront; - UintVector iback; - - VertexLookup vfront = Vl_createVertexLookup(); - VertexLookup vback = Vl_createVertexLookup(); - - - bool showmesh = false; - #if SHOW_MESH - showmesh = true; - #endif - - if ( 0 ) - { - showmesh = true; - for (float x=-1; x<1; x+=0.10f) - { - for (float y=0; y<1; y+=0.10f) - { - for (float z=-1; z<1; z+=0.04f) - { - float d = x*plane[0] + y*plane[1] + z*plane[2] + plane[3]; - Vector3d p(x,y,z); - if ( d >= 0 ) - callback->ConvexDebugPoint(p.Ptr(), 0.02f, 0x00FF00); - else - callback->ConvexDebugPoint(p.Ptr(), 0.02f, 0xFF0000); - } - } - } - } - - if ( 1 ) - { - // ok..now we are going to 'split' all of the input triangles against this plane! - const unsigned int *source = indices; - for (unsigned int i=0; i 4 || bcount > 4 ) - { - result = planeTriIntersection(plane,t.mP1.Ptr(),sizeof(Vector3d),0.00001f,front[0].Ptr(),fcount,back[0].Ptr(),bcount ); - } - - switch ( result ) - { - case PTR_FRONT: - - assert( fcount == 3 ); - - if ( showmesh ) - callback->ConvexDebugTri( front[0].Ptr(), front[1].Ptr(), front[2].Ptr(), 0x00FF00 ); - - #if MAKE_MESH - - addTri( vfront, ifront, front[0], front[1], front[2] ); - - - #endif - - break; - case PTR_BACK: - assert( bcount == 3 ); - - if ( showmesh ) - callback->ConvexDebugTri( back[0].Ptr(), back[1].Ptr(), back[2].Ptr(), 0xFFFF00 ); - - #if MAKE_MESH - - addTri( vback, iback, back[0], back[1], back[2] ); - - #endif - - break; - case PTR_SPLIT: - - assert( fcount >= 3 && fcount <= 4); - assert( bcount >= 3 && bcount <= 4); - - #if MAKE_MESH - - addTri( vfront, ifront, front[0], front[1], front[2] ); - addTri( vback, iback, back[0], back[1], back[2] ); - - - if ( fcount == 4 ) - { - addTri( vfront, ifront, front[0], front[2], front[3] ); - } - - if ( bcount == 4 ) - { - addTri( vback, iback, back[0], back[2], back[3] ); - } - - #endif - - if ( showmesh ) - { - callback->ConvexDebugTri( front[0].Ptr(), front[1].Ptr(), front[2].Ptr(), 0x00D000 ); - callback->ConvexDebugTri( back[0].Ptr(), back[1].Ptr(), back[2].Ptr(), 0xD0D000 ); - - if ( fcount == 4 ) - { - callback->ConvexDebugTri( front[0].Ptr(), front[2].Ptr(), front[3].Ptr(), 0x00D000 ); - } - if ( bcount == 4 ) - { - callback->ConvexDebugTri( back[0].Ptr(), back[2].Ptr(), back[3].Ptr(), 0xD0D000 ); - } - } - - break; - } - } - - // ok... here we recursively call - if ( ifront.size() ) - { - unsigned int vcount = Vl_getVcount(vfront); - const float *vertices = Vl_getVertices(vfront); - unsigned int tcount = ifront.size()/3; - - calcConvexDecomposition(vcount, vertices, tcount, &ifront[0], callback, masterVolume, depth+1); - - } - - ifront.clear(); - - Vl_releaseVertexLookup(vfront); - - if ( iback.size() ) - { - unsigned int vcount = Vl_getVcount(vback); - const float *vertices = Vl_getVertices(vback); - unsigned int tcount = iback.size()/3; - - calcConvexDecomposition(vcount, vertices, tcount, &iback[0], callback, masterVolume, depth+1); - - } - - iback.clear(); - Vl_releaseVertexLookup(vback); - - } -} - - - - -} diff --git a/extern/bullet/src/Extras/ConvexDecomposition/ConvexDecomposition.h b/extern/bullet/src/Extras/ConvexDecomposition/ConvexDecomposition.h deleted file mode 100644 index 2886c39a49b4..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/ConvexDecomposition.h +++ /dev/null @@ -1,220 +0,0 @@ -#ifndef CONVEX_DECOMPOSITION_H - -#define CONVEX_DECOMPOSITION_H - -/*---------------------------------------------------------------------- -Copyright (c) 2004 Open Dynamics Framework Group -www.physicstools.org -All rights reserved. - -Redistribution and use in source and binary forms, with or without modification, are permitted provided -that the following conditions are met: - -Redistributions of source code must retain the above copyright notice, this list of conditions -and the following disclaimer. - -Redistributions in binary form must reproduce the above copyright notice, -this list of conditions and the following disclaimer in the documentation -and/or other materials provided with the distribution. - -Neither the name of the Open Dynamics Framework Group nor the names of its contributors may -be used to endorse or promote products derived from this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, -INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, -EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER -IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF -THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -// http://codesuppository.blogspot.com -// -// mailto: jratcliff@infiniplex.net -// -// http://www.amillionpixels.us -// - - -#ifdef _WIN32 -#include //memcpy -#endif -#include -#include -#include "LinearMath/btAlignedObjectArray.h" - - - -extern unsigned int MAXDEPTH ; -extern float CONCAVE_PERCENT ; -extern float MERGE_PERCENT ; - - -typedef btAlignedObjectArray< unsigned int > UintVector; - - - -namespace ConvexDecomposition -{ - - class ConvexResult - { - public: - ConvexResult(void) - { - mHullVcount = 0; - mHullVertices = 0; - mHullTcount = 0; - mHullIndices = 0; - } - - ConvexResult(unsigned int hvcount,const float *hvertices,unsigned int htcount,const unsigned int *hindices) - { - mHullVcount = hvcount; - if ( mHullVcount ) - { - mHullVertices = new float[mHullVcount*sizeof(float)*3]; - memcpy(mHullVertices, hvertices, sizeof(float)*3*mHullVcount ); - } - else - { - mHullVertices = 0; - } - - mHullTcount = htcount; - - if ( mHullTcount ) - { - mHullIndices = new unsigned int[sizeof(unsigned int)*mHullTcount*3]; - memcpy(mHullIndices,hindices, sizeof(unsigned int)*mHullTcount*3 ); - } - else - { - mHullIndices = 0; - } - - } - - ConvexResult(const ConvexResult &r) - { - mHullVcount = r.mHullVcount; - if ( mHullVcount ) - { - mHullVertices = new float[mHullVcount*sizeof(float)*3]; - memcpy(mHullVertices, r.mHullVertices, sizeof(float)*3*mHullVcount ); - } - else - { - mHullVertices = 0; - } - mHullTcount = r.mHullTcount; - if ( mHullTcount ) - { - mHullIndices = new unsigned int[sizeof(unsigned int)*mHullTcount*3]; - memcpy(mHullIndices, r.mHullIndices, sizeof(unsigned int)*mHullTcount*3 ); - } - else - { - mHullIndices = 0; - } - } - - ~ConvexResult(void) - { - delete [] mHullVertices; - delete [] mHullIndices; - } - - // the convex hull. - unsigned int mHullVcount; - float * mHullVertices; - unsigned int mHullTcount; - unsigned int *mHullIndices; - - float mHullVolume; // the volume of the convex hull. - - float mOBBSides[3]; // the width, height and breadth of the best fit OBB - float mOBBCenter[3]; // the center of the OBB - float mOBBOrientation[4]; // the quaternion rotation of the OBB. - float mOBBTransform[16]; // the 4x4 transform of the OBB. - float mOBBVolume; // the volume of the OBB - - float mSphereRadius; // radius and center of best fit sphere - float mSphereCenter[3]; - float mSphereVolume; // volume of the best fit sphere - - - - }; - - class ConvexDecompInterface - { - public: - virtual ~ConvexDecompInterface() {}; - virtual void ConvexDebugTri(const float *p1,const float *p2,const float *p3,unsigned int color) { }; - virtual void ConvexDebugPoint(const float *p,float dist,unsigned int color) { }; - virtual void ConvexDebugBound(const float *bmin,const float *bmax,unsigned int color) { }; - virtual void ConvexDebugOBB(const float *sides, const float *matrix,unsigned int color) { }; - - virtual void ConvexDecompResult(ConvexResult &result) = 0; - - - - }; - - // just to avoid passing a zillion parameters to the method the - // options are packed into this descriptor. - class DecompDesc - { - public: - DecompDesc(void) - { - mVcount = 0; - mVertices = 0; - mTcount = 0; - mIndices = 0; - mDepth = 5; - mCpercent = 5; - mPpercent = 5; - mMaxVertices = 32; - mSkinWidth = 0; - mCallback = 0; - } - - // describes the input triangle. - unsigned int mVcount; // the number of vertices in the source mesh. - const float *mVertices; // start of the vertex position array. Assumes a stride of 3 floats. - unsigned int mTcount; // the number of triangles in the source mesh. - unsigned int *mIndices; // the indexed triangle list array (zero index based) - - // options - unsigned int mDepth; // depth to split, a maximum of 10, generally not over 7. - float mCpercent; // the concavity threshold percentage. 0=20 is reasonable. - float mPpercent; // the percentage volume conservation threshold to collapse hulls. 0-30 is reasonable. - - // hull output limits. - unsigned int mMaxVertices; // maximum number of vertices in the output hull. Recommended 32 or less. - float mSkinWidth; // a skin width to apply to the output hulls. - - ConvexDecompInterface *mCallback; // the interface to receive back the results. - - }; - - // perform approximate convex decomposition on a mesh. - unsigned int performConvexDecomposition(const DecompDesc &desc); // returns the number of hulls produced. - - - void calcConvexDecomposition(unsigned int vcount, - const float *vertices, - unsigned int tcount, - const unsigned int *indices, - ConvexDecompInterface *callback, - float masterVolume, - unsigned int depth); - - -} - - -#endif diff --git a/extern/bullet/src/Extras/ConvexDecomposition/bestfit.cpp b/extern/bullet/src/Extras/ConvexDecomposition/bestfit.cpp deleted file mode 100644 index e6469f6fb455..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/bestfit.cpp +++ /dev/null @@ -1,466 +0,0 @@ -#include "float_math.h" -#include -#include -#include -#include -#include - -/*---------------------------------------------------------------------- - Copyright (c) 2004 Open Dynamics Framework Group - www.physicstools.org - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are permitted provided - that the following conditions are met: - - Redistributions of source code must retain the above copyright notice, this list of conditions - and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - Neither the name of the Open Dynamics Framework Group nor the names of its contributors may - be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER - IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -// http://codesuppository.blogspot.com -// -// mailto: jratcliff@infiniplex.net -// -// http://www.amillionpixels.us -// -// Geometric Tools, Inc. -// http://www.geometrictools.com -// Copyright (c) 1998-2006. All Rights Reserved -// -// The Wild Magic Library (WM3) source code is supplied under the terms of -// the license agreement -// http://www.geometrictools.com/License/WildMagic3License.pdf -// and may not be copied or disclosed except in accordance with the terms -// of that agreement. - -#include "bestfit.h" - -namespace BestFit -{ - -class Vec3 -{ -public: - Vec3(void) { }; - Vec3(float _x,float _y,float _z) { x = _x; y = _y; z = _z; }; - - - float dot(const Vec3 &v) - { - return x*v.x + y*v.y + z*v.z; // the dot product - } - - float x; - float y; - float z; -}; - - -class Eigen -{ -public: - - - void DecrSortEigenStuff(void) - { - Tridiagonal(); //diagonalize the matrix. - QLAlgorithm(); // - DecreasingSort(); - GuaranteeRotation(); - } - - void Tridiagonal(void) - { - float fM00 = mElement[0][0]; - float fM01 = mElement[0][1]; - float fM02 = mElement[0][2]; - float fM11 = mElement[1][1]; - float fM12 = mElement[1][2]; - float fM22 = mElement[2][2]; - - m_afDiag[0] = fM00; - m_afSubd[2] = 0; - if (fM02 != (float)0.0) - { - float fLength = sqrtf(fM01*fM01+fM02*fM02); - float fInvLength = ((float)1.0)/fLength; - fM01 *= fInvLength; - fM02 *= fInvLength; - float fQ = ((float)2.0)*fM01*fM12+fM02*(fM22-fM11); - m_afDiag[1] = fM11+fM02*fQ; - m_afDiag[2] = fM22-fM02*fQ; - m_afSubd[0] = fLength; - m_afSubd[1] = fM12-fM01*fQ; - mElement[0][0] = (float)1.0; - mElement[0][1] = (float)0.0; - mElement[0][2] = (float)0.0; - mElement[1][0] = (float)0.0; - mElement[1][1] = fM01; - mElement[1][2] = fM02; - mElement[2][0] = (float)0.0; - mElement[2][1] = fM02; - mElement[2][2] = -fM01; - m_bIsRotation = false; - } - else - { - m_afDiag[1] = fM11; - m_afDiag[2] = fM22; - m_afSubd[0] = fM01; - m_afSubd[1] = fM12; - mElement[0][0] = (float)1.0; - mElement[0][1] = (float)0.0; - mElement[0][2] = (float)0.0; - mElement[1][0] = (float)0.0; - mElement[1][1] = (float)1.0; - mElement[1][2] = (float)0.0; - mElement[2][0] = (float)0.0; - mElement[2][1] = (float)0.0; - mElement[2][2] = (float)1.0; - m_bIsRotation = true; - } - } - - bool QLAlgorithm(void) - { - const int iMaxIter = 32; - - for (int i0 = 0; i0 <3; i0++) - { - int i1; - for (i1 = 0; i1 < iMaxIter; i1++) - { - int i2; - for (i2 = i0; i2 <= (3-2); i2++) - { - float fTmp = fabsf(m_afDiag[i2]) + fabsf(m_afDiag[i2+1]); - if ( fabsf(m_afSubd[i2]) + fTmp == fTmp ) - break; - } - if (i2 == i0) - { - break; - } - - float fG = (m_afDiag[i0+1] - m_afDiag[i0])/(((float)2.0) * m_afSubd[i0]); - float fR = sqrtf(fG*fG+(float)1.0); - if (fG < (float)0.0) - { - fG = m_afDiag[i2]-m_afDiag[i0]+m_afSubd[i0]/(fG-fR); - } - else - { - fG = m_afDiag[i2]-m_afDiag[i0]+m_afSubd[i0]/(fG+fR); - } - float fSin = (float)1.0, fCos = (float)1.0, fP = (float)0.0; - for (int i3 = i2-1; i3 >= i0; i3--) - { - float fF = fSin*m_afSubd[i3]; - float fB = fCos*m_afSubd[i3]; - if (fabsf(fF) >= fabsf(fG)) - { - fCos = fG/fF; - fR = sqrtf(fCos*fCos+(float)1.0); - m_afSubd[i3+1] = fF*fR; - fSin = ((float)1.0)/fR; - fCos *= fSin; - } - else - { - fSin = fF/fG; - fR = sqrtf(fSin*fSin+(float)1.0); - m_afSubd[i3+1] = fG*fR; - fCos = ((float)1.0)/fR; - fSin *= fCos; - } - fG = m_afDiag[i3+1]-fP; - fR = (m_afDiag[i3]-fG)*fSin+((float)2.0)*fB*fCos; - fP = fSin*fR; - m_afDiag[i3+1] = fG+fP; - fG = fCos*fR-fB; - for (int i4 = 0; i4 < 3; i4++) - { - fF = mElement[i4][i3+1]; - mElement[i4][i3+1] = fSin*mElement[i4][i3]+fCos*fF; - mElement[i4][i3] = fCos*mElement[i4][i3]-fSin*fF; - } - } - m_afDiag[i0] -= fP; - m_afSubd[i0] = fG; - m_afSubd[i2] = (float)0.0; - } - if (i1 == iMaxIter) - { - return false; - } - } - return true; - } - - void DecreasingSort(void) - { - //sort eigenvalues in decreasing order, e[0] >= ... >= e[iSize-1] - for (int i0 = 0, i1; i0 <= 3-2; i0++) - { - // locate maximum eigenvalue - i1 = i0; - float fMax = m_afDiag[i1]; - int i2; - for (i2 = i0+1; i2 < 3; i2++) - { - if (m_afDiag[i2] > fMax) - { - i1 = i2; - fMax = m_afDiag[i1]; - } - } - - if (i1 != i0) - { - // swap eigenvalues - m_afDiag[i1] = m_afDiag[i0]; - m_afDiag[i0] = fMax; - // swap eigenvectors - for (i2 = 0; i2 < 3; i2++) - { - float fTmp = mElement[i2][i0]; - mElement[i2][i0] = mElement[i2][i1]; - mElement[i2][i1] = fTmp; - m_bIsRotation = !m_bIsRotation; - } - } - } - } - - - void GuaranteeRotation(void) - { - if (!m_bIsRotation) - { - // change sign on the first column - for (int iRow = 0; iRow <3; iRow++) - { - mElement[iRow][0] = -mElement[iRow][0]; - } - } - } - - float mElement[3][3]; - float m_afDiag[3]; - float m_afSubd[3]; - bool m_bIsRotation; -}; - -} - - -using namespace BestFit; - - -bool getBestFitPlane(unsigned int vcount, - const float *points, - unsigned int vstride, - const float *weights, - unsigned int wstride, - float *plane) -{ - bool ret = false; - - Vec3 kOrigin(0,0,0); - - float wtotal = 0; - - if ( 1 ) - { - const char *source = (const char *) points; - const char *wsource = (const char *) weights; - - for (unsigned int i=0; i bmax[0] ) bmax[0] = p[0]; - if ( p[1] > bmax[1] ) bmax[1] = p[1]; - if ( p[2] > bmax[2] ) bmax[2] = p[2]; - - } - - float dx = bmax[0] - bmin[0]; - float dy = bmax[1] - bmin[1]; - float dz = bmax[2] - bmin[2]; - - return sqrtf( dx*dx + dy*dy + dz*dz ); - -} - - -bool overlapAABB(const float *bmin1,const float *bmax1,const float *bmin2,const float *bmax2) // return true if the two AABB's overlap. -{ - if ( bmax2[0] < bmin1[0] ) return false; // if the maximum is less than our minimum on any axis - if ( bmax2[1] < bmin1[1] ) return false; - if ( bmax2[2] < bmin1[2] ) return false; - - if ( bmin2[0] > bmax1[0] ) return false; // if the minimum is greater than our maximum on any axis - if ( bmin2[1] > bmax1[1] ) return false; // if the minimum is greater than our maximum on any axis - if ( bmin2[2] > bmax1[2] ) return false; // if the minimum is greater than our maximum on any axis - - - return true; // the extents overlap -} - - diff --git a/extern/bullet/src/Extras/ConvexDecomposition/bestfit.h b/extern/bullet/src/Extras/ConvexDecomposition/bestfit.h deleted file mode 100644 index f2e78e5a6049..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/bestfit.h +++ /dev/null @@ -1,65 +0,0 @@ -#ifndef BEST_FIT_H - -#define BEST_FIT_H - -/*---------------------------------------------------------------------- - Copyright (c) 2004 Open Dynamics Framework Group - www.physicstools.org - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are permitted provided - that the following conditions are met: - - Redistributions of source code must retain the above copyright notice, this list of conditions - and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - Neither the name of the Open Dynamics Framework Group nor the names of its contributors may - be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER - IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -// http://codesuppository.blogspot.com -// -// mailto: jratcliff@infiniplex.net -// -// http://www.amillionpixels.us -// - - -// This routine was released in 'snippet' form -// by John W. Ratcliff mailto:jratcliff@infiniplex.net -// on March 22, 2006. -// -// This routine computes the 'best fit' plane equation to -// a set of input data points with an optional per vertex -// weighting component. -// -// The implementation for this was lifted directly from -// David Eberly's Magic Software implementation. - -// computes the best fit plane to a collection of data points. -// returns the plane equation as A,B,C,D format. (Ax+By+Cz+D) - -bool getBestFitPlane(unsigned int vcount, // number of input data points - const float *points, // starting address of points array. - unsigned int vstride, // stride between input points. - const float *weights, // *optional point weighting values. - unsigned int wstride, // weight stride for each vertex. - float *plane); - - -float getBoundingRegion(unsigned int vcount,const float *points,unsigned int pstride,float *bmin,float *bmax); // returns the diagonal distance -bool overlapAABB(const float *bmin1,const float *bmax1,const float *bmin2,const float *bmax2); // return true if the two AABB's overlap. - -#endif diff --git a/extern/bullet/src/Extras/ConvexDecomposition/bestfitobb.cpp b/extern/bullet/src/Extras/ConvexDecomposition/bestfitobb.cpp deleted file mode 100644 index 2d60fd0450e4..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/bestfitobb.cpp +++ /dev/null @@ -1,173 +0,0 @@ -#include "float_math.h" - -#include -#include -#include -#include -#include - -/*---------------------------------------------------------------------- - Copyright (c) 2004 Open Dynamics Framework Group - www.physicstools.org - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are permitted provided - that the following conditions are met: - - Redistributions of source code must retain the above copyright notice, this list of conditions - and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - Neither the name of the Open Dynamics Framework Group nor the names of its contributors may - be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER - IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -// http://codesuppository.blogspot.com -// -// mailto: jratcliff@infiniplex.net -// -// http://www.amillionpixels.us -// - -#include "bestfitobb.h" -#include "float_math.h" - -// computes the OBB for this set of points relative to this transform matrix. -void computeOBB(unsigned int vcount,const float *points,unsigned int pstride,float *sides,const float *matrix) -{ - const char *src = (const char *) points; - - float bmin[3] = { 1e9, 1e9, 1e9 }; - float bmax[3] = { -1e9, -1e9, -1e9 }; - - for (unsigned int i=0; i bmax[0] ) bmax[0] = t[0]; - if ( t[1] > bmax[1] ) bmax[1] = t[1]; - if ( t[2] > bmax[2] ) bmax[2] = t[2]; - - src+=pstride; - } - - - sides[0] = bmax[0]; - sides[1] = bmax[1]; - sides[2] = bmax[2]; - - if ( fabsf(bmin[0]) > sides[0] ) sides[0] = fabsf(bmin[0]); - if ( fabsf(bmin[1]) > sides[1] ) sides[1] = fabsf(bmin[1]); - if ( fabsf(bmin[2]) > sides[2] ) sides[2] = fabsf(bmin[2]); - - sides[0]*=2.0f; - sides[1]*=2.0f; - sides[2]*=2.0f; - -} - -void computeBestFitOBB(unsigned int vcount,const float *points,unsigned int pstride,float *sides,float *matrix) -{ - - float bmin[3]; - float bmax[3]; - - fm_getAABB(vcount,points,pstride,bmin,bmax); - - float center[3]; - - center[0] = (bmax[0]-bmin[0])*0.5f + bmin[0]; - center[1] = (bmax[1]-bmin[1])*0.5f + bmin[1]; - center[2] = (bmax[2]-bmin[2])*0.5f + bmin[2]; - - float ax = 0; - float ay = 0; - float az = 0; - - float sweep = 45.0f; // 180 degree sweep on all three axes. - float steps = 8.0f; // 16 steps on each axis. - - float bestVolume = 1e9; - float angle[3]={0.f,0.f,0.f}; - - while ( sweep >= 1 ) - { - - bool found = false; - - float stepsize = sweep / steps; - - for (float x=ax-sweep; x<=ax+sweep; x+=stepsize) - { - for (float y=ay-sweep; y<=ay+sweep; y+=stepsize) - { - for (float z=az-sweep; z<=az+sweep; z+=stepsize) - { - float pmatrix[16]; - - fm_eulerMatrix( x*FM_DEG_TO_RAD, y*FM_DEG_TO_RAD, z*FM_DEG_TO_RAD, pmatrix ); - - pmatrix[3*4+0] = center[0]; - pmatrix[3*4+1] = center[1]; - pmatrix[3*4+2] = center[2]; - - float psides[3]; - - computeOBB( vcount, points, pstride, psides, pmatrix ); - - float volume = psides[0]*psides[1]*psides[2]; // the volume of the cube - - if ( volume <= bestVolume ) - { - bestVolume = volume; - - sides[0] = psides[0]; - sides[1] = psides[1]; - sides[2] = psides[2]; - - angle[0] = ax; - angle[1] = ay; - angle[2] = az; - - memcpy(matrix,pmatrix,sizeof(float)*16); - found = true; // yes, we found an improvement. - } - } - } - } - - if ( found ) - { - - ax = angle[0]; - ay = angle[1]; - az = angle[2]; - - sweep*=0.5f; // sweep 1/2 the distance as the last time. - } - else - { - break; // no improvement, so just - } - - } - -} diff --git a/extern/bullet/src/Extras/ConvexDecomposition/bestfitobb.h b/extern/bullet/src/Extras/ConvexDecomposition/bestfitobb.h deleted file mode 100644 index 3141f5874d5c..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/bestfitobb.h +++ /dev/null @@ -1,43 +0,0 @@ -#ifndef BEST_FIT_OBB_H - -#define BEST_FIT_OBB_H - -/*---------------------------------------------------------------------- - Copyright (c) 2004 Open Dynamics Framework Group - www.physicstools.org - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are permitted provided - that the following conditions are met: - - Redistributions of source code must retain the above copyright notice, this list of conditions - and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - Neither the name of the Open Dynamics Framework Group nor the names of its contributors may - be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER - IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -// http://codesuppository.blogspot.com -// -// mailto: jratcliff@infiniplex.net -// -// http://www.amillionpixels.us -// - - - -void computeBestFitOBB(unsigned int vcount,const float *points,unsigned int pstride,float *sides,float *matrix); - -#endif diff --git a/extern/bullet/src/Extras/ConvexDecomposition/cd_hull.cpp b/extern/bullet/src/Extras/ConvexDecomposition/cd_hull.cpp deleted file mode 100644 index 0fc8b51e0409..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/cd_hull.cpp +++ /dev/null @@ -1,3261 +0,0 @@ -#include "float_math.h" - -#include -#include -#include -#include -#include -#include - -/*---------------------------------------------------------------------- - Copyright (c) 2004 Open Dynamics Framework Group - www.physicstools.org - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are permitted provided - that the following conditions are met: - - Redistributions of source code must retain the above copyright notice, this list of conditions - and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - Neither the name of the Open Dynamics Framework Group nor the names of its contributors may - be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER - IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -// http://codesuppository.blogspot.com -// -// mailto: jratcliff@infiniplex.net -// -// http://www.amillionpixels.us -// - -#include "cd_hull.h" - -using namespace ConvexDecomposition; - -/*---------------------------------------------------------------------- - Copyright (c) 2004 Open Dynamics Framework Group - www.physicstools.org - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are permitted provided - that the following conditions are met: - - Redistributions of source code must retain the above copyright notice, this list of conditions - and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - Neither the name of the Open Dynamics Framework Group nor the names of its contributors may - be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER - IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -#define PI 3.14159264f - -//***************************************************** -//***************************************************** -//********* Stan Melax's vector math template needed -//********* to use his hull building code. -//***************************************************** -//***************************************************** - -#define DEG2RAD (PI / 180.0f) -#define RAD2DEG (180.0f / PI) -#define SQRT_OF_2 (1.4142135f) -#define OFFSET(Class,Member) (((char*) (&(((Class*)NULL)-> Member )))- ((char*)NULL)) - -namespace ConvexDecomposition -{ - - -int argmin(float a[],int n); -float sqr(float a); -float clampf(float a) ; -float Round(float a,float precision); -float Interpolate(const float &f0,const float &f1,float alpha) ; - -template -void Swap(T &a,T &b) -{ - T tmp = a; - a=b; - b=tmp; -} - - - -template -T Max(const T &a,const T &b) -{ - return (a>b)?a:b; -} - -template -T Min(const T &a,const T &b) -{ - return (a=0&&i<2);return ((float*)this)[i];} - const float& operator[](int i) const {assert(i>=0&&i<2);return ((float*)this)[i];} -}; -inline float2 operator-( const float2& a, const float2& b ){return float2(a.x-b.x,a.y-b.y);} -inline float2 operator+( const float2& a, const float2& b ){return float2(a.x+b.x,a.y+b.y);} - -//--------- 3D --------- - -class float3 // 3D -{ - public: - float x,y,z; - float3(){x=0;y=0;z=0;}; - float3(float _x,float _y,float _z){x=_x;y=_y;z=_z;}; - //operator float *() { return &x;}; - float& operator[](int i) {assert(i>=0&&i<3);return ((float*)this)[i];} - const float& operator[](int i) const {assert(i>=0&&i<3);return ((float*)this)[i];} -# ifdef PLUGIN_3DSMAX - float3(const Point3 &p):x(p.x),y(p.y),z(p.z){} - operator Point3(){return *((Point3*)this);} -# endif -}; - - -float3& operator+=( float3 &a, const float3& b ); -float3& operator-=( float3 &a ,const float3& b ); -float3& operator*=( float3 &v ,const float s ); -float3& operator/=( float3 &v, const float s ); - -float magnitude( const float3& v ); -float3 normalize( const float3& v ); -float3 safenormalize(const float3 &v); -float3 vabs(const float3 &v); -float3 operator+( const float3& a, const float3& b ); -float3 operator-( const float3& a, const float3& b ); -float3 operator-( const float3& v ); -float3 operator*( const float3& v, const float s ); -float3 operator*( const float s, const float3& v ); -float3 operator/( const float3& v, const float s ); -inline int operator==( const float3 &a, const float3 &b ) { return (a.x==b.x && a.y==b.y && a.z==b.z); } -inline int operator!=( const float3 &a, const float3 &b ) { return (a.x!=b.x || a.y!=b.y || a.z!=b.z); } -// due to ambiguity and inconsistent standards ther are no overloaded operators for mult such as va*vb. -float dot( const float3& a, const float3& b ); -float3 cmul( const float3 &a, const float3 &b); -float3 cross( const float3& a, const float3& b ); -float3 Interpolate(const float3 &v0,const float3 &v1,float alpha); -float3 Round(const float3& a,float precision); -float3 VectorMax(const float3 &a, const float3 &b); -float3 VectorMin(const float3 &a, const float3 &b); - - - -class float3x3 -{ - public: - float3 x,y,z; // the 3 rows of the Matrix - float3x3(){} - float3x3(float xx,float xy,float xz,float yx,float yy,float yz,float zx,float zy,float zz):x(xx,xy,xz),y(yx,yy,yz),z(zx,zy,zz){} - float3x3(float3 _x,float3 _y,float3 _z):x(_x),y(_y),z(_z){} - float3& operator[](int i) {assert(i>=0&&i<3);return (&x)[i];} - const float3& operator[](int i) const {assert(i>=0&&i<3);return (&x)[i];} - float& operator()(int r, int c) {assert(r>=0&&r<3&&c>=0&&c<3);return ((&x)[r])[c];} - const float& operator()(int r, int c) const {assert(r>=0&&r<3&&c>=0&&c<3);return ((&x)[r])[c];} -}; -float3x3 Transpose( const float3x3& m ); -float3 operator*( const float3& v , const float3x3& m ); -float3 operator*( const float3x3& m , const float3& v ); -float3x3 operator*( const float3x3& m , const float& s ); -float3x3 operator*( const float3x3& ma, const float3x3& mb ); -float3x3 operator/( const float3x3& a, const float& s ) ; -float3x3 operator+( const float3x3& a, const float3x3& b ); -float3x3 operator-( const float3x3& a, const float3x3& b ); -float3x3 &operator+=( float3x3& a, const float3x3& b ); -float3x3 &operator-=( float3x3& a, const float3x3& b ); -float3x3 &operator*=( float3x3& a, const float& s ); -float Determinant(const float3x3& m ); -float3x3 Inverse(const float3x3& a); // its just 3x3 so we simply do that cofactor method - - -//-------- 4D Math -------- - -class float4 -{ -public: - float x,y,z,w; - float4(){x=0;y=0;z=0;w=0;}; - float4(float _x,float _y,float _z,float _w){x=_x;y=_y;z=_z;w=_w;} - float4(const float3 &v,float _w){x=v.x;y=v.y;z=v.z;w=_w;} - //operator float *() { return &x;}; - float& operator[](int i) {assert(i>=0&&i<4);return ((float*)this)[i];} - const float& operator[](int i) const {assert(i>=0&&i<4);return ((float*)this)[i];} - const float3& xyz() const { return *((float3*)this);} - float3& xyz() { return *((float3*)this);} -}; - - -struct D3DXMATRIX; - -class float4x4 -{ - public: - float4 x,y,z,w; // the 4 rows - float4x4(){} - float4x4(const float4 &_x, const float4 &_y, const float4 &_z, const float4 &_w):x(_x),y(_y),z(_z),w(_w){} - float4x4(float m00, float m01, float m02, float m03, - float m10, float m11, float m12, float m13, - float m20, float m21, float m22, float m23, - float m30, float m31, float m32, float m33 ) - :x(m00,m01,m02,m03),y(m10,m11,m12,m13),z(m20,m21,m22,m23),w(m30,m31,m32,m33){} - float& operator()(int r, int c) {assert(r>=0&&r<4&&c>=0&&c<4);return ((&x)[r])[c];} - const float& operator()(int r, int c) const {assert(r>=0&&r<4&&c>=0&&c<4);return ((&x)[r])[c];} - operator float* () {return &x.x;} - operator const float* () const {return &x.x;} - operator struct D3DXMATRIX* () { return (struct D3DXMATRIX*) this;} - operator const struct D3DXMATRIX* () const { return (struct D3DXMATRIX*) this;} -}; - - -int operator==( const float4 &a, const float4 &b ); -float4 Homogenize(const float3 &v3,const float &w=1.0f); // Turns a 3D float3 4D vector4 by appending w -float4 cmul( const float4 &a, const float4 &b); -float4 operator*( const float4 &v, float s); -float4 operator*( float s, const float4 &v); -float4 operator+( const float4 &a, const float4 &b); -float4 operator-( const float4 &a, const float4 &b); -float4x4 operator*( const float4x4& a, const float4x4& b ); -float4 operator*( const float4& v, const float4x4& m ); -float4x4 Inverse(const float4x4 &m); -float4x4 MatrixRigidInverse(const float4x4 &m); -float4x4 MatrixTranspose(const float4x4 &m); -float4x4 MatrixPerspectiveFov(float fovy, float Aspect, float zn, float zf ); -float4x4 MatrixTranslation(const float3 &t); -float4x4 MatrixRotationZ(const float angle_radians); -float4x4 MatrixLookAt(const float3& eye, const float3& at, const float3& up); -int operator==( const float4x4 &a, const float4x4 &b ); - - -//-------- Quaternion ------------ - -class Quaternion :public float4 -{ - public: - Quaternion() { x = y = z = 0.0f; w = 1.0f; } - Quaternion( float3 v, float t ) { v = normalize(v); w = cosf(t/2.0f); v = v*sinf(t/2.0f); x = v.x; y = v.y; z = v.z; } - Quaternion(float _x, float _y, float _z, float _w){x=_x;y=_y;z=_z;w=_w;} - float angle() const { return acosf(w)*2.0f; } - float3 axis() const { float3 a(x,y,z); if(fabsf(angle())<0.0000001f) return float3(1,0,0); return a*(1/sinf(angle()/2.0f)); } - float3 xdir() const { return float3( 1-2*(y*y+z*z), 2*(x*y+w*z), 2*(x*z-w*y) ); } - float3 ydir() const { return float3( 2*(x*y-w*z),1-2*(x*x+z*z), 2*(y*z+w*x) ); } - float3 zdir() const { return float3( 2*(x*z+w*y), 2*(y*z-w*x),1-2*(x*x+y*y) ); } - float3x3 getmatrix() const { return float3x3( xdir(), ydir(), zdir() ); } - operator float3x3() { return getmatrix(); } - void Normalize(); -}; - -Quaternion& operator*=(Quaternion& a, float s ); -Quaternion operator*( const Quaternion& a, float s ); -Quaternion operator*( const Quaternion& a, const Quaternion& b); -Quaternion operator+( const Quaternion& a, const Quaternion& b ); -Quaternion normalize( Quaternion a ); -float dot( const Quaternion &a, const Quaternion &b ); -float3 operator*( const Quaternion& q, const float3& v ); -float3 operator*( const float3& v, const Quaternion& q ); -Quaternion slerp( Quaternion a, const Quaternion& b, float interp ); -Quaternion Interpolate(const Quaternion &q0,const Quaternion &q1,float alpha); -Quaternion RotationArc(float3 v0, float3 v1 ); // returns quat q where q*v0=v1 -Quaternion Inverse(const Quaternion &q); -float4x4 MatrixFromQuatVec(const Quaternion &q, const float3 &v); - - -//------ Euler Angle ----- - -Quaternion YawPitchRoll( float yaw, float pitch, float roll ); -float Yaw( const Quaternion& q ); -float Pitch( const Quaternion& q ); -float Roll( Quaternion q ); -float Yaw( const float3& v ); -float Pitch( const float3& v ); - - -//------- Plane ---------- - -class Plane -{ - public: - float3 normal; - float dist; // distance below origin - the D from plane equasion Ax+By+Cz+D=0 - Plane(const float3 &n,float d):normal(n),dist(d){} - Plane():normal(),dist(0){} - void Transform(const float3 &position, const Quaternion &orientation); -}; - -inline Plane PlaneFlip(const Plane &plane){return Plane(-plane.normal,-plane.dist);} -inline int operator==( const Plane &a, const Plane &b ) { return (a.normal==b.normal && a.dist==b.dist); } -inline int coplanar( const Plane &a, const Plane &b ) { return (a==b || a==PlaneFlip(b)); } - - -//--------- Utility Functions ------ - -float3 PlaneLineIntersection(const Plane &plane, const float3 &p0, const float3 &p1); -float3 PlaneProject(const Plane &plane, const float3 &point); -float3 LineProject(const float3 &p0, const float3 &p1, const float3 &a); // projects a onto infinite line p0p1 -float LineProjectTime(const float3 &p0, const float3 &p1, const float3 &a); -float3 ThreePlaneIntersection(const Plane &p0,const Plane &p1, const Plane &p2); -int PolyHit(const float3 *vert,const int n,const float3 &v0, const float3 &v1, float3 *impact=NULL, float3 *normal=NULL); -int BoxInside(const float3 &p,const float3 &bmin, const float3 &bmax) ; -int BoxIntersect(const float3 &v0, const float3 &v1, const float3 &bmin, const float3 &bmax, float3 *impact); -float DistanceBetweenLines(const float3 &ustart, const float3 &udir, const float3 &vstart, const float3 &vdir, float3 *upoint=NULL, float3 *vpoint=NULL); -float3 TriNormal(const float3 &v0, const float3 &v1, const float3 &v2); -float3 NormalOf(const float3 *vert, const int n); -Quaternion VirtualTrackBall(const float3 &cop, const float3 &cor, const float3 &dir0, const float3 &dir1); - - -float sqr(float a) {return a*a;} -float clampf(float a) {return Min(1.0f,Max(0.0f,a));} - - -float Round(float a,float precision) -{ - return floorf(0.5f+a/precision)*precision; -} - - -float Interpolate(const float &f0,const float &f1,float alpha) -{ - return f0*(1-alpha) + f1*alpha; -} - - -int argmin(float a[],int n) -{ - int r=0; - for(int i=1;i=1.0) { - return a; - } - float theta = acosf(d); - if(theta==0.0f) { return(a);} - return a*(sinf(theta-interp*theta)/sinf(theta)) + b*(sinf(interp*theta)/sinf(theta)); -} - - -Quaternion Interpolate(const Quaternion &q0,const Quaternion &q1,float alpha) { - return slerp(q0,q1,alpha); -} - - -Quaternion YawPitchRoll( float yaw, float pitch, float roll ) -{ - roll *= DEG2RAD; - yaw *= DEG2RAD; - pitch *= DEG2RAD; - return Quaternion(float3(0.0f,0.0f,1.0f),yaw)*Quaternion(float3(1.0f,0.0f,0.0f),pitch)*Quaternion(float3(0.0f,1.0f,0.0f),roll); -} - -float Yaw( const Quaternion& q ) -{ - float3 v; - v=q.ydir(); - return (v.y==0.0&&v.x==0.0) ? 0.0f: atan2f(-v.x,v.y)*RAD2DEG; -} - -float Pitch( const Quaternion& q ) -{ - float3 v; - v=q.ydir(); - return atan2f(v.z,sqrtf(sqr(v.x)+sqr(v.y)))*RAD2DEG; -} - -float Roll( Quaternion q ) -{ - q = Quaternion(float3(0.0f,0.0f,1.0f),-Yaw(q)*DEG2RAD) *q; - q = Quaternion(float3(1.0f,0.0f,0.0f),-Pitch(q)*DEG2RAD) *q; - return atan2f(-q.xdir().z,q.xdir().x)*RAD2DEG; -} - -float Yaw( const float3& v ) -{ - return (v.y==0.0&&v.x==0.0) ? 0.0f: atan2f(-v.x,v.y)*RAD2DEG; -} - -float Pitch( const float3& v ) -{ - return atan2f(v.z,sqrtf(sqr(v.x)+sqr(v.y)))*RAD2DEG; -} - - -//------------- Plane -------------- - - -void Plane::Transform(const float3 &position, const Quaternion &orientation) { - // Transforms the plane to the space defined by the - // given position/orientation. - float3 newnormal; - float3 origin; - - newnormal = Inverse(orientation)*normal; - origin = Inverse(orientation)*(-normal*dist - position); - - normal = newnormal; - dist = -dot(newnormal, origin); -} - - - - -//--------- utility functions ------------- - -// RotationArc() -// Given two vectors v0 and v1 this function -// returns quaternion q where q*v0==v1. -// Routine taken from game programming gems. -Quaternion RotationArc(float3 v0,float3 v1){ - Quaternion q; - v0 = normalize(v0); // Comment these two lines out if you know its not needed. - v1 = normalize(v1); // If vector is already unit length then why do it again? - float3 c = cross(v0,v1); - float d = dot(v0,v1); - if(d<=-1.0f) { return Quaternion(1,0,0,0);} // 180 about x axis - float s = sqrtf((1+d)*2); - q.x = c.x / s; - q.y = c.y / s; - q.z = c.z / s; - q.w = s /2.0f; - return q; -} - - -float4x4 MatrixFromQuatVec(const Quaternion &q, const float3 &v) -{ - // builds a 4x4 transformation matrix based on orientation q and translation v - float qx2 = q.x*q.x; - float qy2 = q.y*q.y; - float qz2 = q.z*q.z; - - float qxqy = q.x*q.y; - float qxqz = q.x*q.z; - float qxqw = q.x*q.w; - float qyqz = q.y*q.z; - float qyqw = q.y*q.w; - float qzqw = q.z*q.w; - - return float4x4( - 1-2*(qy2+qz2), - 2*(qxqy+qzqw), - 2*(qxqz-qyqw), - 0 , - 2*(qxqy-qzqw), - 1-2*(qx2+qz2), - 2*(qyqz+qxqw), - 0 , - 2*(qxqz+qyqw), - 2*(qyqz-qxqw), - 1-2*(qx2+qy2), - 0 , - v.x , - v.y , - v.z , - 1.0f ); -} - - -float3 PlaneLineIntersection(const Plane &plane, const float3 &p0, const float3 &p1) -{ - // returns the point where the line p0-p1 intersects the plane n&d - float3 dif; - dif = p1-p0; - float dn= dot(plane.normal,dif); - float t = -(plane.dist+dot(plane.normal,p0) )/dn; - return p0 + (dif*t); -} - -float3 PlaneProject(const Plane &plane, const float3 &point) -{ - return point - plane.normal * (dot(point,plane.normal)+plane.dist); -} - -float3 LineProject(const float3 &p0, const float3 &p1, const float3 &a) -{ - float3 w; - w = p1-p0; - float t= dot(w,(a-p0)) / (sqr(w.x)+sqr(w.y)+sqr(w.z)); - return p0+ w*t; -} - - -float LineProjectTime(const float3 &p0, const float3 &p1, const float3 &a) -{ - float3 w; - w = p1-p0; - float t= dot(w,(a-p0)) / (sqr(w.x)+sqr(w.y)+sqr(w.z)); - return t; -} - - - -float3 TriNormal(const float3 &v0, const float3 &v1, const float3 &v2) -{ - // return the normal of the triangle - // inscribed by v0, v1, and v2 - float3 cp=cross(v1-v0,v2-v1); - float m=magnitude(cp); - if(m==0) return float3(1,0,0); - return cp*(1.0f/m); -} - - - -int BoxInside(const float3 &p, const float3 &bmin, const float3 &bmax) -{ - return (p.x >= bmin.x && p.x <=bmax.x && - p.y >= bmin.y && p.y <=bmax.y && - p.z >= bmin.z && p.z <=bmax.z ); -} - - -int BoxIntersect(const float3 &v0, const float3 &v1, const float3 &bmin, const float3 &bmax,float3 *impact) -{ - if(BoxInside(v0,bmin,bmax)) - { - *impact=v0; - return 1; - } - if(v0.x<=bmin.x && v1.x>=bmin.x) - { - float a = (bmin.x-v0.x)/(v1.x-v0.x); - //v.x = bmin.x; - float vy = (1-a) *v0.y + a*v1.y; - float vz = (1-a) *v0.z + a*v1.z; - if(vy>=bmin.y && vy<=bmax.y && vz>=bmin.z && vz<=bmax.z) - { - impact->x = bmin.x; - impact->y = vy; - impact->z = vz; - return 1; - } - } - else if(v0.x >= bmax.x && v1.x <= bmax.x) - { - float a = (bmax.x-v0.x)/(v1.x-v0.x); - //v.x = bmax.x; - float vy = (1-a) *v0.y + a*v1.y; - float vz = (1-a) *v0.z + a*v1.z; - if(vy>=bmin.y && vy<=bmax.y && vz>=bmin.z && vz<=bmax.z) - { - impact->x = bmax.x; - impact->y = vy; - impact->z = vz; - return 1; - } - } - if(v0.y<=bmin.y && v1.y>=bmin.y) - { - float a = (bmin.y-v0.y)/(v1.y-v0.y); - float vx = (1-a) *v0.x + a*v1.x; - //v.y = bmin.y; - float vz = (1-a) *v0.z + a*v1.z; - if(vx>=bmin.x && vx<=bmax.x && vz>=bmin.z && vz<=bmax.z) - { - impact->x = vx; - impact->y = bmin.y; - impact->z = vz; - return 1; - } - } - else if(v0.y >= bmax.y && v1.y <= bmax.y) - { - float a = (bmax.y-v0.y)/(v1.y-v0.y); - float vx = (1-a) *v0.x + a*v1.x; - // vy = bmax.y; - float vz = (1-a) *v0.z + a*v1.z; - if(vx>=bmin.x && vx<=bmax.x && vz>=bmin.z && vz<=bmax.z) - { - impact->x = vx; - impact->y = bmax.y; - impact->z = vz; - return 1; - } - } - if(v0.z<=bmin.z && v1.z>=bmin.z) - { - float a = (bmin.z-v0.z)/(v1.z-v0.z); - float vx = (1-a) *v0.x + a*v1.x; - float vy = (1-a) *v0.y + a*v1.y; - // v.z = bmin.z; - if(vy>=bmin.y && vy<=bmax.y && vx>=bmin.x && vx<=bmax.x) - { - impact->x = vx; - impact->y = vy; - impact->z = bmin.z; - return 1; - } - } - else if(v0.z >= bmax.z && v1.z <= bmax.z) - { - float a = (bmax.z-v0.z)/(v1.z-v0.z); - float vx = (1-a) *v0.x + a*v1.x; - float vy = (1-a) *v0.y + a*v1.y; - // v.z = bmax.z; - if(vy>=bmin.y && vy<=bmax.y && vx>=bmin.x && vx<=bmax.x) - { - impact->x = vx; - impact->y = vy; - impact->z = bmax.z; - return 1; - } - } - return 0; -} - - -float DistanceBetweenLines(const float3 &ustart, const float3 &udir, const float3 &vstart, const float3 &vdir, float3 *upoint, float3 *vpoint) -{ - float3 cp; - cp = normalize(cross(udir,vdir)); - - float distu = -dot(cp,ustart); - float distv = -dot(cp,vstart); - float dist = (float)fabs(distu-distv); - if(upoint) - { - Plane plane; - plane.normal = normalize(cross(vdir,cp)); - plane.dist = -dot(plane.normal,vstart); - *upoint = PlaneLineIntersection(plane,ustart,ustart+udir); - } - if(vpoint) - { - Plane plane; - plane.normal = normalize(cross(udir,cp)); - plane.dist = -dot(plane.normal,ustart); - *vpoint = PlaneLineIntersection(plane,vstart,vstart+vdir); - } - return dist; -} - - -Quaternion VirtualTrackBall(const float3 &cop, const float3 &cor, const float3 &dir1, const float3 &dir2) -{ - // routine taken from game programming gems. - // Implement track ball functionality to spin stuf on the screen - // cop center of projection - // cor center of rotation - // dir1 old mouse direction - // dir2 new mouse direction - // pretend there is a sphere around cor. Then find the points - // where dir1 and dir2 intersect that sphere. Find the - // rotation that takes the first point to the second. - float m; - // compute plane - float3 nrml = cor - cop; - float fudgefactor = 1.0f/(magnitude(nrml) * 0.25f); // since trackball proportional to distance from cop - nrml = normalize(nrml); - float dist = -dot(nrml,cor); - float3 u= PlaneLineIntersection(Plane(nrml,dist),cop,cop+dir1); - u=u-cor; - u=u*fudgefactor; - m= magnitude(u); - if(m>1) - { - u/=m; - } - else - { - u=u - (nrml * sqrtf(1-m*m)); - } - float3 v= PlaneLineIntersection(Plane(nrml,dist),cop,cop+dir2); - v=v-cor; - v=v*fudgefactor; - m= magnitude(v); - if(m>1) - { - v/=m; - } - else - { - v=v - (nrml * sqrtf(1-m*m)); - } - return RotationArc(u,v); -} - - -int countpolyhit=0; -int PolyHit(const float3 *vert, const int n, const float3 &v0, const float3 &v1, float3 *impact, float3 *normal) -{ - countpolyhit++; - int i; - float3 nrml(0,0,0); - for(i=0;i0) - { - return 0; - } - - float3 the_point; - // By using the cached plane distances d0 and d1 - // we can optimize the following: - // the_point = planelineintersection(nrml,dist,v0,v1); - float a = d0/(d0-d1); - the_point = v0*(1-a) + v1*a; - - - int inside=1; - for(int j=0;inside && j= 0.0); - } - if(inside) - { - if(normal){*normal=nrml;} - if(impact){*impact=the_point;} - } - return inside; -} - -//************************************************************************** -//************************************************************************** -//*** Stan Melax's array template, needed to compile his hull generation code -//************************************************************************** -//************************************************************************** - -template class ArrayRet; -template class Array { - public: - Array(int s=0); - Array(Array &array); - Array(ArrayRet &array); - ~Array(); - void allocate(int s); - void SetSize(int s); - void Pack(); - Type& Add(Type); - void AddUnique(Type); - int Contains(Type); - void Insert(Type,int); - int IndexOf(Type); - void Remove(Type); - void DelIndex(int i); - Type * element; - int count; - int array_size; - const Type &operator[](int i) const { assert(i>=0 && i=0 && i &operator=(Array &array); - Array &operator=(ArrayRet &array); - // operator ArrayRet &() { return *(ArrayRet *)this;} // this worked but i suspect could be dangerous -}; - -template class ArrayRet:public Array -{ -}; - -template Array::Array(int s) -{ - count=0; - array_size = 0; - element = NULL; - if(s) - { - allocate(s); - } -} - - -template Array::Array(Array &array) -{ - count=0; - array_size = 0; - element = NULL; - for(int i=0;i Array::Array(ArrayRet &array) -{ - *this = array; -} -template Array &Array::operator=(ArrayRet &array) -{ - count=array.count; - array_size = array.array_size; - element = array.element; - array.element=NULL; - array.count=0; - array.array_size=0; - return *this; -} - - -template Array &Array::operator=(Array &array) -{ - count=0; - for(int i=0;i Array::~Array() -{ - if (element != NULL) - { - free(element); - } - count=0;array_size=0;element=NULL; -} - -template void Array::allocate(int s) -{ - assert(s>0); - assert(s>=count); - Type *old = element; - array_size =s; - element = (Type *) malloc( sizeof(Type)*array_size); - assert(element); - for(int i=0;i void Array::SetSize(int s) -{ - if(s==0) - { - if(element) - { - free(element); - element = NULL; - } - array_size = s; - } - else - { - allocate(s); - } - count=s; -} - -template void Array::Pack() -{ - allocate(count); -} - -template Type& Array::Add(Type t) -{ - assert(count<=array_size); - if(count==array_size) - { - allocate((array_size)?array_size *2:16); - } - element[count++] = t; - return element[count-1]; -} - -template int Array::Contains(Type t) -{ - int i; - int found=0; - for(i=0;i void Array::AddUnique(Type t) -{ - if(!Contains(t)) Add(t); -} - - -template void Array::DelIndex(int i) -{ - assert(i void Array::Remove(Type t) -{ - int i; - for(i=0;i void Array::Insert(Type t,int k) -{ - int i=count; - Add(t); // to allocate space - while(i>k) - { - element[i]=element[i-1]; - i--; - } - assert(i==k); - element[k]=t; -} - - -template int Array::IndexOf(Type t) -{ - int i; - for(i=0;i vertices; - Array edges; - Array facets; - ConvexH(int vertices_size,int edges_size,int facets_size); -}; - -typedef ConvexH::HalfEdge HalfEdge; - -ConvexH::ConvexH(int vertices_size,int edges_size,int facets_size) - :vertices(vertices_size) - ,edges(edges_size) - ,facets(facets_size) -{ - vertices.count=vertices_size; - edges.count = edges_size; - facets.count = facets_size; -} - -ConvexH *ConvexHDup(ConvexH *src) { - ConvexH *dst = new ConvexH(src->vertices.count,src->edges.count,src->facets.count); - memcpy(dst->vertices.element,src->vertices.element,sizeof(float3)*src->vertices.count); - memcpy(dst->edges.element,src->edges.element,sizeof(HalfEdge)*src->edges.count); - memcpy(dst->facets.element,src->facets.element,sizeof(Plane)*src->facets.count); - return dst; -} - - -int PlaneTest(const Plane &p, const REAL3 &v) { - REAL a = dot(v,p.normal)+p.dist; - int flag = (a>planetestepsilon)?OVER:((a<-planetestepsilon)?UNDER:COPLANAR); - return flag; -} - -int SplitTest(ConvexH &convex,const Plane &plane) { - int flag=0; - for(int i=0;i= convex.edges.count || convex.edges[inext].p != convex.edges[i].p) { - inext = estart; - } - assert(convex.edges[inext].p == convex.edges[i].p); - int nb = convex.edges[i].ea; - assert(nb!=255); - if(nb==255 || nb==-1) return 0; - assert(nb!=-1); - assert(i== convex.edges[nb].ea); - } - for(i=0;i= convex.edges.count || convex.edges[i1].p != convex.edges[i].p) { - i1 = estart; - } - int i2 = i1+1; - if(i2>= convex.edges.count || convex.edges[i2].p != convex.edges[i].p) { - i2 = estart; - } - if(i==i2) continue; // i sliced tangent to an edge and created 2 meaningless edges - REAL3 localnormal = TriNormal(convex.vertices[convex.edges[i ].v], - convex.vertices[convex.edges[i1].v], - convex.vertices[convex.edges[i2].v]); - assert(dot(localnormal,convex.facets[convex.edges[i].p].normal)>0); - if(dot(localnormal,convex.facets[convex.edges[i].p].normal)<=0)return 0; - } - return 1; -} - -// back to back quads -ConvexH *test_btbq() { - ConvexH *convex = new ConvexH(4,8,2); - convex->vertices[0] = REAL3(0,0,0); - convex->vertices[1] = REAL3(1,0,0); - convex->vertices[2] = REAL3(1,1,0); - convex->vertices[3] = REAL3(0,1,0); - convex->facets[0] = Plane(REAL3(0,0,1),0); - convex->facets[1] = Plane(REAL3(0,0,-1),0); - convex->edges[0] = HalfEdge(7,0,0); - convex->edges[1] = HalfEdge(6,1,0); - convex->edges[2] = HalfEdge(5,2,0); - convex->edges[3] = HalfEdge(4,3,0); - - convex->edges[4] = HalfEdge(3,0,1); - convex->edges[5] = HalfEdge(2,3,1); - convex->edges[6] = HalfEdge(1,2,1); - convex->edges[7] = HalfEdge(0,1,1); - AssertIntact(*convex); - return convex; -} -ConvexH *test_cube() { - ConvexH *convex = new ConvexH(8,24,6); - convex->vertices[0] = REAL3(0,0,0); - convex->vertices[1] = REAL3(0,0,1); - convex->vertices[2] = REAL3(0,1,0); - convex->vertices[3] = REAL3(0,1,1); - convex->vertices[4] = REAL3(1,0,0); - convex->vertices[5] = REAL3(1,0,1); - convex->vertices[6] = REAL3(1,1,0); - convex->vertices[7] = REAL3(1,1,1); - - convex->facets[0] = Plane(REAL3(-1,0,0),0); - convex->facets[1] = Plane(REAL3(1,0,0),-1); - convex->facets[2] = Plane(REAL3(0,-1,0),0); - convex->facets[3] = Plane(REAL3(0,1,0),-1); - convex->facets[4] = Plane(REAL3(0,0,-1),0); - convex->facets[5] = Plane(REAL3(0,0,1),-1); - - convex->edges[0 ] = HalfEdge(11,0,0); - convex->edges[1 ] = HalfEdge(23,1,0); - convex->edges[2 ] = HalfEdge(15,3,0); - convex->edges[3 ] = HalfEdge(16,2,0); - - convex->edges[4 ] = HalfEdge(13,6,1); - convex->edges[5 ] = HalfEdge(21,7,1); - convex->edges[6 ] = HalfEdge( 9,5,1); - convex->edges[7 ] = HalfEdge(18,4,1); - - convex->edges[8 ] = HalfEdge(19,0,2); - convex->edges[9 ] = HalfEdge( 6,4,2); - convex->edges[10] = HalfEdge(20,5,2); - convex->edges[11] = HalfEdge( 0,1,2); - - convex->edges[12] = HalfEdge(22,3,3); - convex->edges[13] = HalfEdge( 4,7,3); - convex->edges[14] = HalfEdge(17,6,3); - convex->edges[15] = HalfEdge( 2,2,3); - - convex->edges[16] = HalfEdge( 3,0,4); - convex->edges[17] = HalfEdge(14,2,4); - convex->edges[18] = HalfEdge( 7,6,4); - convex->edges[19] = HalfEdge( 8,4,4); - - convex->edges[20] = HalfEdge(10,1,5); - convex->edges[21] = HalfEdge( 5,5,5); - convex->edges[22] = HalfEdge(12,7,5); - convex->edges[23] = HalfEdge( 1,3,5); - - - return convex; -} -ConvexH *ConvexHMakeCube(const REAL3 &bmin, const REAL3 &bmax) { - ConvexH *convex = test_cube(); - convex->vertices[0] = REAL3(bmin.x,bmin.y,bmin.z); - convex->vertices[1] = REAL3(bmin.x,bmin.y,bmax.z); - convex->vertices[2] = REAL3(bmin.x,bmax.y,bmin.z); - convex->vertices[3] = REAL3(bmin.x,bmax.y,bmax.z); - convex->vertices[4] = REAL3(bmax.x,bmin.y,bmin.z); - convex->vertices[5] = REAL3(bmax.x,bmin.y,bmax.z); - convex->vertices[6] = REAL3(bmax.x,bmax.y,bmin.z); - convex->vertices[7] = REAL3(bmax.x,bmax.y,bmax.z); - - convex->facets[0] = Plane(REAL3(-1,0,0), bmin.x); - convex->facets[1] = Plane(REAL3(1,0,0), -bmax.x); - convex->facets[2] = Plane(REAL3(0,-1,0), bmin.y); - convex->facets[3] = Plane(REAL3(0,1,0), -bmax.y); - convex->facets[4] = Plane(REAL3(0,0,-1), bmin.z); - convex->facets[5] = Plane(REAL3(0,0,1), -bmax.z); - return convex; -} -ConvexH *ConvexHCrop(ConvexH &convex,const Plane &slice) -{ - int i; - int vertcountunder=0; - int vertcountover =0; - Array vertscoplanar; // existing vertex members of convex that are coplanar - vertscoplanar.count=0; - Array edgesplit; // existing edges that members of convex that cross the splitplane - edgesplit.count=0; - - assert(convex.edges.count<480); - - EdgeFlag edgeflag[512]; - VertFlag vertflag[256]; - PlaneFlag planeflag[128]; - HalfEdge tmpunderedges[512]; - Plane tmpunderplanes[128]; - Coplanar coplanaredges[512]; - int coplanaredges_num=0; - - Array createdverts; - // do the side-of-plane tests - for(i=0;i= convex.edges.count || convex.edges[e1].p!=currentplane) { - enextface = e1; - e1=estart; - } - HalfEdge &edge0 = convex.edges[e0]; - HalfEdge &edge1 = convex.edges[e1]; - HalfEdge &edgea = convex.edges[edge0.ea]; - - - planeside |= vertflag[edge0.v].planetest; - //if((vertflag[edge0.v].planetest & vertflag[edge1.v].planetest) == COPLANAR) { - // assert(ecop==-1); - // ecop=e; - //} - - - if(vertflag[edge0.v].planetest == OVER && vertflag[edge1.v].planetest == OVER){ - // both endpoints over plane - edgeflag[e0].undermap = -1; - } - else if((vertflag[edge0.v].planetest | vertflag[edge1.v].planetest) == UNDER) { - // at least one endpoint under, the other coplanar or under - - edgeflag[e0].undermap = under_edge_count; - tmpunderedges[under_edge_count].v = vertflag[edge0.v].undermap; - tmpunderedges[under_edge_count].p = underplanescount; - if(edge0.ea < e0) { - // connect the neighbors - assert(edgeflag[edge0.ea].undermap !=-1); - tmpunderedges[under_edge_count].ea = edgeflag[edge0.ea].undermap; - tmpunderedges[edgeflag[edge0.ea].undermap].ea = under_edge_count; - } - under_edge_count++; - } - else if((vertflag[edge0.v].planetest | vertflag[edge1.v].planetest) == COPLANAR) { - // both endpoints coplanar - // must check a 3rd point to see if UNDER - int e2 = e1+1; - if(e2>=convex.edges.count || convex.edges[e2].p!=currentplane) { - e2 = estart; - } - assert(convex.edges[e2].p==currentplane); - HalfEdge &edge2 = convex.edges[e2]; - if(vertflag[edge2.v].planetest==UNDER) { - - edgeflag[e0].undermap = under_edge_count; - tmpunderedges[under_edge_count].v = vertflag[edge0.v].undermap; - tmpunderedges[under_edge_count].p = underplanescount; - tmpunderedges[under_edge_count].ea = -1; - // make sure this edge is added to the "coplanar" list - coplanaredge = under_edge_count; - vout = vertflag[edge0.v].undermap; - vin = vertflag[edge1.v].undermap; - under_edge_count++; - } - else { - edgeflag[e0].undermap = -1; - } - } - else if(vertflag[edge0.v].planetest == UNDER && vertflag[edge1.v].planetest == OVER) { - // first is under 2nd is over - - edgeflag[e0].undermap = under_edge_count; - tmpunderedges[under_edge_count].v = vertflag[edge0.v].undermap; - tmpunderedges[under_edge_count].p = underplanescount; - if(edge0.ea < e0) { - assert(edgeflag[edge0.ea].undermap !=-1); - // connect the neighbors - tmpunderedges[under_edge_count].ea = edgeflag[edge0.ea].undermap; - tmpunderedges[edgeflag[edge0.ea].undermap].ea = under_edge_count; - vout = tmpunderedges[edgeflag[edge0.ea].undermap].v; - } - else { - Plane &p0 = convex.facets[edge0.p]; - Plane &pa = convex.facets[edgea.p]; - createdverts.Add(ThreePlaneIntersection(p0,pa,slice)); - //createdverts.Add(PlaneProject(slice,PlaneLineIntersection(slice,convex.vertices[edge0.v],convex.vertices[edgea.v]))); - //createdverts.Add(PlaneLineIntersection(slice,convex.vertices[edge0.v],convex.vertices[edgea.v])); - vout = vertcountunder++; - } - under_edge_count++; - /// hmmm something to think about: i might be able to output this edge regarless of - // wheter or not we know v-in yet. ok i;ll try this now: - tmpunderedges[under_edge_count].v = vout; - tmpunderedges[under_edge_count].p = underplanescount; - tmpunderedges[under_edge_count].ea = -1; - coplanaredge = under_edge_count; - under_edge_count++; - - if(vin!=-1) { - // we previously processed an edge where we came under - // now we know about vout as well - - // ADD THIS EDGE TO THE LIST OF EDGES THAT NEED NEIGHBOR ON PARTITION PLANE!! - } - - } - else if(vertflag[edge0.v].planetest == COPLANAR && vertflag[edge1.v].planetest == OVER) { - // first is coplanar 2nd is over - - edgeflag[e0].undermap = -1; - vout = vertflag[edge0.v].undermap; - // I hate this but i have to make sure part of this face is UNDER before ouputting this vert - int k=estart; - assert(edge0.p == currentplane); - while(!(planeside&UNDER) && k= vertcountunderold); // for debugging only - } - if(vout!=-1) { - // we previously processed an edge where we went over - // now we know vin too - // ADD THIS EDGE TO THE LIST OF EDGES THAT NEED NEIGHBOR ON PARTITION PLANE!! - } - // output edge - tmpunderedges[under_edge_count].v = vin; - tmpunderedges[under_edge_count].p = underplanescount; - edgeflag[e0].undermap = under_edge_count; - if(e0>edge0.ea) { - assert(edgeflag[edge0.ea].undermap !=-1); - // connect the neighbors - tmpunderedges[under_edge_count].ea = edgeflag[edge0.ea].undermap; - tmpunderedges[edgeflag[edge0.ea].undermap].ea = under_edge_count; - } - assert(edgeflag[e0].undermap == under_edge_count); - under_edge_count++; - } - else if(vertflag[edge0.v].planetest == OVER && vertflag[edge1.v].planetest == COPLANAR) { - // first is over next is coplanar - - edgeflag[e0].undermap = -1; - vin = vertflag[edge1.v].undermap; - assert(vin!=-1); - if(vout!=-1) { - // we previously processed an edge where we came under - // now we know both endpoints - // ADD THIS EDGE TO THE LIST OF EDGES THAT NEED NEIGHBOR ON PARTITION PLANE!! - } - - } - else { - assert(0); - } - - - e0=e1; - e1++; // do the modulo at the beginning of the loop - - } while(e0!=estart) ; - e0 = enextface; - if(planeside&UNDER) { - planeflag[currentplane].undermap = underplanescount; - tmpunderplanes[underplanescount] = convex.facets[currentplane]; - underplanescount++; - } - else { - planeflag[currentplane].undermap = 0; - } - if(vout>=0 && (planeside&UNDER)) { - assert(vin>=0); - assert(coplanaredge>=0); - assert(coplanaredge!=511); - coplanaredges[coplanaredges_num].ea = coplanaredge; - coplanaredges[coplanaredges_num].v0 = vin; - coplanaredges[coplanaredges_num].v1 = vout; - coplanaredges_num++; - } - } - - // add the new plane to the mix: - if(coplanaredges_num>0) { - tmpunderplanes[underplanescount++]=slice; - } - for(i=0;i=coplanaredges_num) - { - assert(jvertices.count;j++) - { - d = Max(d,dot(convex->vertices[j],planes[i].normal)+planes[i].dist); - } - if(i==0 || d>md) - { - p=i; - md=d; - } - } - return (md>epsilon)?p:-1; -} - -template -inline int maxdir(const T *p,int count,const T &dir) -{ - assert(count); - int m=0; - float currDotm = dot(p[0], dir); - for(int i=1;i currDotm) - { - currDotm = currDoti; - m=i; - } - } - return m; -} - - -template -int maxdirfiltered(const T *p,int count,const T &dir,Array &allow) -{ - assert(count); - int m=-1; - float currDotm = dot(p[0], dir); - for(int i=0;icurrDotm) - { - currDotm = currDoti; - m=i; - } - } - } - } - assert(m!=-1); - return m; -} - -float3 orth(const float3 &v) -{ - float3 a=cross(v,float3(0,0,1)); - float3 b=cross(v,float3(0,1,0)); - return normalize((magnitude(a)>magnitude(b))?a:b); -} - - -template -int maxdirsterid(const T *p,int count,const T &dir,Array &allow) -{ - int m=-1; - while(m==-1) - { - m = maxdirfiltered(p,count,dir,allow); - if(allow[m]==3) return m; - T u = orth(dir); - T v = cross(u,dir); - int ma=-1; - for(float x = 0.0f ; x<= 360.0f ; x+= 45.0f) - { - float s = sinf(DEG2RAD*(x)); - float c = cosf(DEG2RAD*(x)); - int mb = maxdirfiltered(p,count,dir+(u*s+v*c)*0.025f,allow); - if(ma==m && mb==m) - { - allow[m]=3; - return m; - } - if(ma!=-1 && ma!=mb) // Yuck - this is really ugly - { - int mc = ma; - for(float xx = x-40.0f ; xx <= x ; xx+= 5.0f) - { - float s = sinf(DEG2RAD*(xx)); - float c = cosf(DEG2RAD*(xx)); - int md = maxdirfiltered(p,count,dir+(u*s+v*c)*0.025f,allow); - if(mc==m && md==m) - { - allow[m]=3; - return m; - } - mc=md; - } - } - ma=mb; - } - allow[m]=0; - m=-1; - } - assert(0); - return m; -} - - - - -int operator ==(const int3 &a,const int3 &b) -{ - for(int i=0;i<3;i++) - { - if(a[i]!=b[i]) return 0; - } - return 1; -} - -int3 roll3(int3 a) -{ - int tmp=a[0]; - a[0]=a[1]; - a[1]=a[2]; - a[2]=tmp; - return a; -} -int isa(const int3 &a,const int3 &b) -{ - return ( a==b || roll3(a)==b || a==roll3(b) ); -} -int b2b(const int3 &a,const int3 &b) -{ - return isa(a,int3(b[2],b[1],b[0])); -} -int above(float3* vertices,const int3& t, const float3 &p, float epsilon) -{ - float3 n=TriNormal(vertices[t[0]],vertices[t[1]],vertices[t[2]]); - return (dot(n,p-vertices[t[0]]) > epsilon); // EPSILON??? -} -int hasedge(const int3 &t, int a,int b) -{ - for(int i=0;i<3;i++) - { - int i1= (i+1)%3; - if(t[i]==a && t[i1]==b) return 1; - } - return 0; -} -int hasvert(const int3 &t, int v) -{ - return (t[0]==v || t[1]==v || t[2]==v) ; -} -int shareedge(const int3 &a,const int3 &b) -{ - int i; - for(i=0;i<3;i++) - { - int i1= (i+1)%3; - if(hasedge(a,b[i1],b[i])) return 1; - } - return 0; -} - -class btHullTriangle; - -//Array tris; - -class btHullTriangle : public int3 -{ -public: - int3 n; - int id; - int vmax; - float rise; - Array* tris; - btHullTriangle(int a,int b,int c, Array* pTris):int3(a,b,c),n(-1,-1,-1) - { - tris = pTris; - id = tris->count; - tris->Add(this); - vmax=-1; - rise = 0.0f; - } - ~btHullTriangle() - { - assert((*tris)[id]==this); - (*tris)[id]=NULL; - } - int &neib(int a,int b); -}; - - -int &btHullTriangle::neib(int a,int b) -{ - static int er=-1; - int i; - for(i=0;i<3;i++) - { - int i1=(i+1)%3; - int i2=(i+2)%3; - if((*this)[i]==a && (*this)[i1]==b) return n[i2]; - if((*this)[i]==b && (*this)[i1]==a) return n[i2]; - } - assert(0); - return er; -} -void b2bfix(btHullTriangle* s,btHullTriangle*t, Array& tris) -{ - int i; - for(i=0;i<3;i++) - { - int i1=(i+1)%3; - int i2=(i+2)%3; - int a = (*s)[i1]; - int b = (*s)[i2]; - assert(tris[s->neib(a,b)]->neib(b,a) == s->id); - assert(tris[t->neib(a,b)]->neib(b,a) == t->id); - tris[s->neib(a,b)]->neib(b,a) = t->neib(b,a); - tris[t->neib(b,a)]->neib(a,b) = s->neib(a,b); - } -} - -void removeb2b(btHullTriangle* s,btHullTriangle*t, Array& tris) -{ - b2bfix(s,t, tris); - delete s; - delete t; -} - -void checkit(btHullTriangle *t, Array& tris) -{ - int i; - assert(tris[t->id]==t); - for(i=0;i<3;i++) - { - int i1=(i+1)%3; - int i2=(i+2)%3; - int a = (*t)[i1]; - int b = (*t)[i2]; - assert(a!=b); - assert( tris[t->n[i]]->neib(b,a) == t->id); - } -} -void extrude(btHullTriangle *t0,int v, Array& tris) -{ - int3 t= *t0; - int n = tris.count; - btHullTriangle* ta = new btHullTriangle(v,t[1],t[2], &tris); - ta->n = int3(t0->n[0],n+1,n+2); - tris[t0->n[0]]->neib(t[1],t[2]) = n+0; - btHullTriangle* tb = new btHullTriangle(v,t[2],t[0], &tris); - tb->n = int3(t0->n[1],n+2,n+0); - tris[t0->n[1]]->neib(t[2],t[0]) = n+1; - btHullTriangle* tc = new btHullTriangle(v,t[0],t[1], &tris); - tc->n = int3(t0->n[2],n+0,n+1); - tris[t0->n[2]]->neib(t[0],t[1]) = n+2; - checkit(ta, tris); - checkit(tb, tris); - checkit(tc, tris); - if(hasvert(*tris[ta->n[0]],v)) removeb2b(ta,tris[ta->n[0]], tris); - if(hasvert(*tris[tb->n[0]],v)) removeb2b(tb,tris[tb->n[0]], tris); - if(hasvert(*tris[tc->n[0]],v)) removeb2b(tc,tris[tc->n[0]], tris); - delete t0; - -} - -btHullTriangle *extrudable(float epsilon, Array& tris) -{ - int i; - btHullTriangle *t=NULL; - for(i=0;iriserise)) - { - t = tris[i]; - } - } - return (t->rise >epsilon)?t:NULL ; -} - -class int4 -{ -public: - int x,y,z,w; - int4(){}; - int4(int _x,int _y, int _z,int _w){x=_x;y=_y;z=_z;w=_w;} - const int& operator[](int i) const {return (&x)[i];} - int& operator[](int i) {return (&x)[i];} -}; - - - -int4 FindSimplex(float3 *verts,int verts_count,Array &allow) -{ - float3 basis[3]; - basis[0] = float3( 0.01f, 0.02f, 1.0f ); - int p0 = maxdirsterid(verts,verts_count, basis[0],allow); - int p1 = maxdirsterid(verts,verts_count,-basis[0],allow); - basis[0] = verts[p0]-verts[p1]; - if(p0==p1 || basis[0]==float3(0,0,0)) - return int4(-1,-1,-1,-1); - basis[1] = cross(float3( 1, 0.02f, 0),basis[0]); - basis[2] = cross(float3(-0.02f, 1, 0),basis[0]); - basis[1] = normalize( (magnitude(basis[1])>magnitude(basis[2])) ? basis[1]:basis[2]); - int p2 = maxdirsterid(verts,verts_count,basis[1],allow); - if(p2 == p0 || p2 == p1) - { - p2 = maxdirsterid(verts,verts_count,-basis[1],allow); - } - if(p2 == p0 || p2 == p1) - return int4(-1,-1,-1,-1); - basis[1] = verts[p2] - verts[p0]; - basis[2] = normalize(cross(basis[1],basis[0])); - int p3 = maxdirsterid(verts,verts_count,basis[2],allow); - if(p3==p0||p3==p1||p3==p2) p3 = maxdirsterid(verts,verts_count,-basis[2],allow); - if(p3==p0||p3==p1||p3==p2) - return int4(-1,-1,-1,-1); - assert(!(p0==p1||p0==p2||p0==p3||p1==p2||p1==p3||p2==p3)); - if(dot(verts[p3]-verts[p0],cross(verts[p1]-verts[p0],verts[p2]-verts[p0])) <0) {Swap(p2,p3);} - return int4(p0,p1,p2,p3); -} - -int calchullgen(float3 *verts,int verts_count, int vlimit,Array& tris) -{ - if(verts_count <4) return 0; - if(vlimit==0) vlimit=1000000000; - int j; - float3 bmin(*verts),bmax(*verts); - Array isextreme(verts_count); - Array allow(verts_count); - for(j=0;jn=int3(2,3,1); - btHullTriangle *t1 = new btHullTriangle(p[3],p[2],p[0], &tris); t1->n=int3(3,2,0); - btHullTriangle *t2 = new btHullTriangle(p[0],p[1],p[3], &tris); t2->n=int3(0,1,3); - btHullTriangle *t3 = new btHullTriangle(p[1],p[0],p[2], &tris); t3->n=int3(1,0,2); - isextreme[p[0]]=isextreme[p[1]]=isextreme[p[2]]=isextreme[p[3]]=1; - checkit(t0, tris);checkit(t1, tris);checkit(t2, tris);checkit(t3, tris); - - for(j=0;jvmax<0); - float3 n=TriNormal(verts[(*t)[0]],verts[(*t)[1]],verts[(*t)[2]]); - t->vmax = maxdirsterid(verts,verts_count,n,allow); - t->rise = dot(n,verts[t->vmax]-verts[(*t)[0]]); - } - btHullTriangle *te; - vlimit-=4; - while(vlimit >0 && (te=extrudable(epsilon, tris))) - { - // int3 ti=*te; - int v=te->vmax; - assert(!isextreme[v]); // wtf we've already done this vertex - isextreme[v]=1; - //if(v==p0 || v==p1 || v==p2 || v==p3) continue; // done these already - j=tris.count; - while(j--) { - if(!tris[j]) continue; - int3 t=*tris[j]; - if(above(verts,t,verts[v],0.01f*epsilon)) - { - extrude(tris[j],v, tris); - } - } - // now check for those degenerate cases where we have a flipped triangle or a really skinny triangle - j=tris.count; - while(j--) - { - if(!tris[j]) continue; - if(!hasvert(*tris[j],v)) break; - int3 nt=*tris[j]; - if(above(verts,nt,center,0.01f*epsilon) || magnitude(cross(verts[nt[1]]-verts[nt[0]],verts[nt[2]]-verts[nt[1]]))< epsilon*epsilon*0.1f ) - { - btHullTriangle *nb = tris[tris[j]->n[0]]; - assert(nb);assert(!hasvert(*nb,v));assert(nb->idvmax>=0) break; - float3 n=TriNormal(verts[(*t)[0]],verts[(*t)[1]],verts[(*t)[2]]); - t->vmax = maxdirsterid(verts,verts_count,n,allow); - if(isextreme[t->vmax]) - { - t->vmax=-1; // already done that vertex - algorithm needs to be able to terminate. - } - else - { - t->rise = dot(n,verts[t->vmax]-verts[(*t)[0]]); - } - } - vlimit --; - } - return 1; -} - -int calchull(float3 *verts,int verts_count, int *&tris_out, int &tris_count,int vlimit, Array& tris) -{ - int rc=calchullgen(verts,verts_count, vlimit, tris) ; - if(!rc) return 0; - Array ts; - for(int i=0;i &planes,float bevangle, Array& tris) -{ - int i,j; - planes.count=0; - int rc = calchullgen(verts,verts_count,vlimit, tris); - if(!rc) return 0; - for(i=0;in[j]id) continue; - btHullTriangle *s = tris[t->n[j]]; - REAL3 snormal = TriNormal(verts[(*s)[0]],verts[(*s)[1]],verts[(*s)[2]]); - if(dot(snormal,p.normal)>=cos(bevangle*DEG2RAD)) continue; - REAL3 n = normalize(snormal+p.normal); - planes.Add(Plane(n,-dot(n,verts[maxdir(verts,verts_count,n)]))); - } - } - - for(i=0;i=0) - { - ConvexH *tmp = c; - c = ConvexHCrop(*tmp,planes[k]); - if(c==NULL) {c=tmp; break;} // might want to debug this case better!!! - if(!AssertIntact(*c)) {c=tmp; break;} // might want to debug this case better too!!! - delete tmp; - } - - assert(AssertIntact(*c)); - //return c; - faces_out = (int*)malloc(sizeof(int)*(1+c->facets.count+c->edges.count)); // new int[1+c->facets.count+c->edges.count]; - faces_count_out=0; - i=0; - faces_out[faces_count_out++]=-1; - k=0; - while(iedges.count) - { - j=1; - while(j+iedges.count && c->edges[i].p==c->edges[i+j].p) { j++; } - faces_out[faces_count_out++]=j; - while(j--) - { - faces_out[faces_count_out++] = c->edges[i].v; - i++; - } - k++; - } - faces_out[0]=k; // number of faces. - assert(k==c->facets.count); - assert(faces_count_out == 1+c->facets.count+c->edges.count); - verts_out = c->vertices.element; // new float3[c->vertices.count]; - verts_count_out = c->vertices.count; - for(i=0;ivertices.count;i++) - { - verts_out[i] = float3(c->vertices[i]); - } - c->vertices.count=c->vertices.array_size=0; c->vertices.element=NULL; - delete c; - return 1; -} - -int overhullv(float3 *verts, int verts_count,int maxplanes, - float3 *&verts_out, int &verts_count_out, int *&faces_out, int &faces_count_out ,float inflate,float bevangle,int vlimit, Array& tris) -{ - if(!verts_count) return 0; - extern int calchullpbev(float3 *verts,int verts_count,int vlimit, Array &planes,float bevangle, Array& tris) ; - Array planes; - int rc=calchullpbev(verts,verts_count,vlimit,planes,bevangle, tris) ; - if(!rc) return 0; - return overhull(planes.element,planes.count,verts,verts_count,maxplanes,verts_out,verts_count_out,faces_out,faces_count_out,inflate); -} - - -bool ComputeHull(unsigned int vcount,const float *vertices,PHullResult &result,unsigned int vlimit,float inflate, Array& arrtris) -{ - - int index_count; - int *faces; - float3 *verts_out; - int verts_count_out; - - if(inflate==0.0f) - { - int *tris_out; - int tris_count; - int ret = calchull( (float3 *) vertices, (int) vcount, tris_out, tris_count, vlimit, arrtris ); - if(!ret) return false; - result.mIndexCount = (unsigned int) (tris_count*3); - result.mFaceCount = (unsigned int) tris_count; - result.mVertices = (float*) vertices; - result.mVcount = (unsigned int) vcount; - result.mIndices = (unsigned int *) tris_out; - return true; - } - - int ret = overhullv((float3*)vertices,vcount,35,verts_out,verts_count_out,faces,index_count,inflate,120.0f,vlimit, arrtris); - if(!ret) return false; - - Array tris; - int n=faces[0]; - int k=1; - for(int i=0;i tris; - ok = ComputeHull(ovcount,vsource,hr,desc.mMaxVertices,skinwidth, tris); - - if ( ok ) - { - - // re-index triangle mesh so it refers to only used vertices, rebuild a new vertex table. - float *vscratch = (float *) malloc( sizeof(float)*hr.mVcount*3); - BringOutYourDead(hr.mVertices,hr.mVcount, vscratch, ovcount, hr.mIndices, hr.mIndexCount ); - - ret = QE_OK; - - if ( desc.HasHullFlag(QF_TRIANGLES) ) // if he wants the results as triangle! - { - result.mPolygons = false; - result.mNumOutputVertices = ovcount; - result.mOutputVertices = (float *)malloc( sizeof(float)*ovcount*3); - result.mNumFaces = hr.mFaceCount; - result.mNumIndices = hr.mIndexCount; - - result.mIndices = (unsigned int *) malloc( sizeof(unsigned int)*hr.mIndexCount); - - memcpy(result.mOutputVertices, vscratch, sizeof(float)*3*ovcount ); - - if ( desc.HasHullFlag(QF_REVERSE_ORDER) ) - { - - const unsigned int *source = hr.mIndices; - unsigned int *dest = result.mIndices; - - for (unsigned int i=0; i bmax[j] ) bmax[j] = p[j]; - } - } - } - - float dx = bmax[0] - bmin[0]; - float dy = bmax[1] - bmin[1]; - float dz = bmax[2] - bmin[2]; - - float center[3]; - - center[0] = dx*0.5f + bmin[0]; - center[1] = dy*0.5f + bmin[1]; - center[2] = dz*0.5f + bmin[2]; - - if ( dx < EPSILON || dy < EPSILON || dz < EPSILON || svcount < 3 ) - { - - float len = FLT_MAX; - - if ( dx > EPSILON && dx < len ) len = dx; - if ( dy > EPSILON && dy < len ) len = dy; - if ( dz > EPSILON && dz < len ) len = dz; - - if ( len == FLT_MAX ) - { - dx = dy = dz = 0.01f; // one centimeter - } - else - { - if ( dx < EPSILON ) dx = len * 0.05f; // 1/5th the shortest non-zero edge. - if ( dy < EPSILON ) dy = len * 0.05f; - if ( dz < EPSILON ) dz = len * 0.05f; - } - - float x1 = center[0] - dx; - float x2 = center[0] + dx; - - float y1 = center[1] - dy; - float y2 = center[1] + dy; - - float z1 = center[2] - dz; - float z2 = center[2] + dz; - - addPoint(vcount,vertices,x1,y1,z1); - addPoint(vcount,vertices,x2,y1,z1); - addPoint(vcount,vertices,x2,y2,z1); - addPoint(vcount,vertices,x1,y2,z1); - addPoint(vcount,vertices,x1,y1,z2); - addPoint(vcount,vertices,x2,y1,z2); - addPoint(vcount,vertices,x2,y2,z2); - addPoint(vcount,vertices,x1,y2,z2); - - return true; // return cube - - - } - else - { - if ( scale ) - { - scale[0] = dx; - scale[1] = dy; - scale[2] = dz; - - recip[0] = 1 / dx; - recip[1] = 1 / dy; - recip[2] = 1 / dz; - - center[0]*=recip[0]; - center[1]*=recip[1]; - center[2]*=recip[2]; - - } - - } - - - - vtx = (const char *) svertices; - - for (unsigned int i=0; i dist2 ) - { - v[0] = px; - v[1] = py; - v[2] = pz; - } - - break; - } - } - - if ( j == vcount ) - { - float *dest = &vertices[vcount*3]; - dest[0] = px; - dest[1] = py; - dest[2] = pz; - vcount++; - } - } - } - - // ok..now make sure we didn't prune so many vertices it is now invalid. - if ( 1 ) - { - float bmin[3] = { FLT_MAX, FLT_MAX, FLT_MAX }; - float bmax[3] = { -FLT_MAX, -FLT_MAX, -FLT_MAX }; - - for (unsigned int i=0; i bmax[j] ) bmax[j] = p[j]; - } - } - - float dx = bmax[0] - bmin[0]; - float dy = bmax[1] - bmin[1]; - float dz = bmax[2] - bmin[2]; - - if ( dx < EPSILON || dy < EPSILON || dz < EPSILON || vcount < 3) - { - float cx = dx*0.5f + bmin[0]; - float cy = dy*0.5f + bmin[1]; - float cz = dz*0.5f + bmin[2]; - - float len = FLT_MAX; - - if ( dx >= EPSILON && dx < len ) len = dx; - if ( dy >= EPSILON && dy < len ) len = dy; - if ( dz >= EPSILON && dz < len ) len = dz; - - if ( len == FLT_MAX ) - { - dx = dy = dz = 0.01f; // one centimeter - } - else - { - if ( dx < EPSILON ) dx = len * 0.05f; // 1/5th the shortest non-zero edge. - if ( dy < EPSILON ) dy = len * 0.05f; - if ( dz < EPSILON ) dz = len * 0.05f; - } - - float x1 = cx - dx; - float x2 = cx + dx; - - float y1 = cy - dy; - float y2 = cy + dy; - - float z1 = cz - dz; - float z2 = cz + dz; - - vcount = 0; // add box - - addPoint(vcount,vertices,x1,y1,z1); - addPoint(vcount,vertices,x2,y1,z1); - addPoint(vcount,vertices,x2,y2,z1); - addPoint(vcount,vertices,x1,y2,z1); - addPoint(vcount,vertices,x1,y1,z2); - addPoint(vcount,vertices,x2,y1,z2); - addPoint(vcount,vertices,x2,y2,z2); - addPoint(vcount,vertices,x1,y2,z2); - - return true; - } - } - - return true; -} - -void HullLibrary::BringOutYourDead(const float *verts,unsigned int vcount, float *overts,unsigned int &ocount,unsigned int *indices,unsigned indexcount) -{ - unsigned int *used = (unsigned int *)malloc(sizeof(unsigned int)*vcount); - memset(used,0,sizeof(unsigned int)*vcount); - - ocount = 0; - - for (unsigned int i=0; i= 0 && v < vcount ); - - if ( used[v] ) // if already remapped - { - indices[i] = used[v]-1; // index to new array - } - else - { - - indices[i] = ocount; // new index mapping - - overts[ocount*3+0] = verts[v*3+0]; // copy old vert to new vert array - overts[ocount*3+1] = verts[v*3+1]; - overts[ocount*3+2] = verts[v*3+2]; - - ocount++; // increment output vert count - - assert( ocount >=0 && ocount <= vcount ); - - used[v] = ocount; // assign new index remapping - } - } - - free(used); -} - -} diff --git a/extern/bullet/src/Extras/ConvexDecomposition/cd_hull.h b/extern/bullet/src/Extras/ConvexDecomposition/cd_hull.h deleted file mode 100644 index 420e241b2e6a..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/cd_hull.h +++ /dev/null @@ -1,153 +0,0 @@ -#ifndef CD_HULL_H - -#define CD_HULL_H - -/*---------------------------------------------------------------------- - Copyright (c) 2004 Open Dynamics Framework Group - www.physicstools.org - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are permitted provided - that the following conditions are met: - - Redistributions of source code must retain the above copyright notice, this list of conditions - and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - Neither the name of the Open Dynamics Framework Group nor the names of its contributors may - be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER - IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -namespace ConvexDecomposition -{ - -class HullResult -{ -public: - HullResult(void) - { - mPolygons = true; - mNumOutputVertices = 0; - mOutputVertices = 0; - mNumFaces = 0; - mNumIndices = 0; - mIndices = 0; - } - bool mPolygons; // true if indices represents polygons, false indices are triangles - unsigned int mNumOutputVertices; // number of vertices in the output hull - float *mOutputVertices; // array of vertices, 3 floats each x,y,z - unsigned int mNumFaces; // the number of faces produced - unsigned int mNumIndices; // the total number of indices - unsigned int *mIndices; // pointer to indices. - -// If triangles, then indices are array indexes into the vertex list. -// If polygons, indices are in the form (number of points in face) (p1, p2, p3, ..) etc.. -}; - -enum HullFlag -{ - QF_TRIANGLES = (1<<0), // report results as triangles, not polygons. - QF_REVERSE_ORDER = (1<<1), // reverse order of the triangle indices. - QF_SKIN_WIDTH = (1<<2), // extrude hull based on this skin width - QF_DEFAULT = 0 -}; - - -class HullDesc -{ -public: - HullDesc(void) - { - mFlags = QF_DEFAULT; - mVcount = 0; - mVertices = 0; - mVertexStride = sizeof(float)*3; - mNormalEpsilon = 0.001f; - mMaxVertices = 4096; // maximum number of points to be considered for a convex hull. - mMaxFaces = 4096; - mSkinWidth = 0.01f; // default is one centimeter - }; - - HullDesc(HullFlag flag, - unsigned int vcount, - const float *vertices, - unsigned int stride) - { - mFlags = flag; - mVcount = vcount; - mVertices = vertices; - mVertexStride = stride; - mNormalEpsilon = 0.001f; - mMaxVertices = 4096; - mSkinWidth = 0.01f; // default is one centimeter - } - - bool HasHullFlag(HullFlag flag) const - { - if ( mFlags & flag ) return true; - return false; - } - - void SetHullFlag(HullFlag flag) - { - mFlags|=flag; - } - - void ClearHullFlag(HullFlag flag) - { - mFlags&=~flag; - } - - unsigned int mFlags; // flags to use when generating the convex hull. - unsigned int mVcount; // number of vertices in the input point cloud - const float *mVertices; // the array of vertices. - unsigned int mVertexStride; // the stride of each vertex, in bytes. - float mNormalEpsilon; // the epsilon for removing duplicates. This is a normalized value, if normalized bit is on. - float mSkinWidth; - unsigned int mMaxVertices; // maximum number of vertices to be considered for the hull! - unsigned int mMaxFaces; -}; - -enum HullError -{ - QE_OK, // success! - QE_FAIL // failed. -}; - -class HullLibrary -{ -public: - - HullError CreateConvexHull(const HullDesc &desc, // describes the input request - HullResult &result); // contains the resulst - - HullError ReleaseResult(HullResult &result); // release memory allocated for this result, we are done with it. - -private: - - void BringOutYourDead(const float *verts,unsigned int vcount, float *overts,unsigned int &ocount,unsigned int *indices,unsigned indexcount); - - bool CleanupVertices(unsigned int svcount, - const float *svertices, - unsigned int stride, - unsigned int &vcount, // output number of vertices - float *vertices, // location to store the results. - float normalepsilon, - float *scale); -}; - -} - -#endif - diff --git a/extern/bullet/src/Extras/ConvexDecomposition/cd_vector.h b/extern/bullet/src/Extras/ConvexDecomposition/cd_vector.h deleted file mode 100644 index bd1eff25b37f..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/cd_vector.h +++ /dev/null @@ -1,1185 +0,0 @@ -#ifndef CD_VECTOR_H - -#define CD_VECTOR_H - -/*---------------------------------------------------------------------- - Copyright (c) 2004 Open Dynamics Framework Group - www.physicstools.org - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are permitted provided - that the following conditions are met: - - Redistributions of source code must retain the above copyright notice, this list of conditions - and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - Neither the name of the Open Dynamics Framework Group nor the names of its contributors may - be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER - IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -// http://codesuppository.blogspot.com -// -// mailto: jratcliff@infiniplex.net -// -// http://www.amillionpixels.us -// - - -#pragma warning(disable:4786) - -#include -#include -#include - -namespace ConvexDecomposition -{ - - -const float DEG_TO_RAD = ((2.0f * 3.14152654f) / 360.0f); -const float RAD_TO_DEG = (360.0f / (2.0f * 3.141592654f)); - -class Vector3d -{ -public: - Vector3d(void) { }; // null constructor, does not inialize point. - - Vector3d(const Vector3d &a) // constructor copies existing vector. - { - x = a.x; - y = a.y; - z = a.z; - }; - - Vector3d(float a,float b,float c) // construct with initial point. - { - x = a; - y = b; - z = c; - }; - - Vector3d(const float *t) - { - x = t[0]; - y = t[1]; - z = t[2]; - }; - - Vector3d(const int *t) - { - x = t[0]; - y = t[1]; - z = t[2]; - }; - - bool operator==(const Vector3d &a) const - { - return( a.x == x && a.y == y && a.z == z ); - }; - - bool operator!=(const Vector3d &a) const - { - return( a.x != x || a.y != y || a.z != z ); - }; - -// Operators - Vector3d& operator = (const Vector3d& A) // ASSIGNMENT (=) - { x=A.x; y=A.y; z=A.z; - return(*this); }; - - Vector3d operator + (const Vector3d& A) const // ADDITION (+) - { Vector3d Sum(x+A.x, y+A.y, z+A.z); - return(Sum); }; - - Vector3d operator - (const Vector3d& A) const // SUBTRACTION (-) - { Vector3d Diff(x-A.x, y-A.y, z-A.z); - return(Diff); }; - - Vector3d operator * (const float s) const // MULTIPLY BY SCALAR (*) - { Vector3d Scaled(x*s, y*s, z*s); - return(Scaled); }; - - - Vector3d operator + (const float s) const // ADD CONSTANT TO ALL 3 COMPONENTS (*) - { Vector3d Scaled(x+s, y+s, z+s); - return(Scaled); }; - - - - - Vector3d operator / (const float s) const // DIVIDE BY SCALAR (/) - { - float r = 1.0f / s; - Vector3d Scaled(x*r, y*r, z*r); - return(Scaled); - }; - - void operator /= (float A) // ACCUMULATED VECTOR ADDITION (/=) - { x/=A; y/=A; z/=A; }; - - void operator += (const Vector3d A) // ACCUMULATED VECTOR ADDITION (+=) - { x+=A.x; y+=A.y; z+=A.z; }; - void operator -= (const Vector3d A) // ACCUMULATED VECTOR SUBTRACTION (+=) - { x-=A.x; y-=A.y; z-=A.z; }; - void operator *= (const float s) // ACCUMULATED SCALAR MULTIPLICATION (*=) (bpc 4/24/2000) - {x*=s; y*=s; z*=s;} - - void operator += (const float A) // ACCUMULATED VECTOR ADDITION (+=) - { x+=A; y+=A; z+=A; }; - - - Vector3d operator - (void) const // NEGATION (-) - { Vector3d Negated(-x, -y, -z); - return(Negated); }; - - float operator [] (const int i) const // ALLOWS VECTOR ACCESS AS AN ARRAY. - { return( (i==0)?x:((i==1)?y:z) ); }; - float & operator [] (const int i) - { return( (i==0)?x:((i==1)?y:z) ); }; -// - - // accessor methods. - float GetX(void) const { return x; }; - float GetY(void) const { return y; }; - float GetZ(void) const { return z; }; - - float X(void) const { return x; }; - float Y(void) const { return y; }; - float Z(void) const { return z; }; - - void SetX(float t) { x = t; }; - void SetY(float t) { y = t; }; - void SetZ(float t) { z = t; }; - - bool IsSame(const Vector3d &v,float epsilon) const - { - float dx = fabsf( x - v.x ); - if ( dx > epsilon ) return false; - float dy = fabsf( y - v.y ); - if ( dy > epsilon ) return false; - float dz = fabsf( z - v.z ); - if ( dz > epsilon ) return false; - return true; - } - - - float ComputeNormal(const Vector3d &A, - const Vector3d &B, - const Vector3d &C) - { - float vx,vy,vz,wx,wy,wz,vw_x,vw_y,vw_z,mag; - - vx = (B.x - C.x); - vy = (B.y - C.y); - vz = (B.z - C.z); - - wx = (A.x - B.x); - wy = (A.y - B.y); - wz = (A.z - B.z); - - vw_x = vy * wz - vz * wy; - vw_y = vz * wx - vx * wz; - vw_z = vx * wy - vy * wx; - - mag = sqrtf((vw_x * vw_x) + (vw_y * vw_y) + (vw_z * vw_z)); - - if ( mag < 0.000001f ) - { - mag = 0; - } - else - { - mag = 1.0f/mag; - } - - x = vw_x * mag; - y = vw_y * mag; - z = vw_z * mag; - - return mag; - } - - - void ScaleSumScale(float c0,float c1,const Vector3d &pos) - { - x = (x*c0) + (pos.x*c1); - y = (y*c0) + (pos.y*c1); - z = (z*c0) + (pos.z*c1); - } - - void SwapYZ(void) - { - float t = y; - y = z; - z = t; - }; - - void Get(float *v) const - { - v[0] = x; - v[1] = y; - v[2] = z; - }; - - void Set(const int *p) - { - x = (float) p[0]; - y = (float) p[1]; - z = (float) p[2]; - } - - void Set(const float *p) - { - x = (float) p[0]; - y = (float) p[1]; - z = (float) p[2]; - } - - - void Set(float a,float b,float c) - { - x = a; - y = b; - z = c; - }; - - void Zero(void) - { - x = y = z = 0; - }; - - const float* Ptr() const { return &x; } - float* Ptr() { return &x; } - - -// return -(*this). - Vector3d negative(void) const - { - Vector3d result; - result.x = -x; - result.y = -y; - result.z = -z; - return result; - } - - float Magnitude(void) const - { - return float(sqrt(x * x + y * y + z * z)); - }; - - float FastMagnitude(void) const - { - return float(sqrtf(x * x + y * y + z * z)); - }; - - float FasterMagnitude(void) const - { - return float(sqrtf(x * x + y * y + z * z)); - }; - - void Lerp(const Vector3d& from,const Vector3d& to,float slerp) - { - x = ((to.x - from.x) * slerp) + from.x; - y = ((to.y - from.y) * slerp) + from.y; - z = ((to.z - from.z) * slerp) + from.z; - }; - - // Highly specialized interpolate routine. Will compute the interpolated position - // shifted forward or backwards along the ray defined between (from) and (to). - // Reason for existance is so that when a bullet collides with a wall, for - // example, you can generate a graphic effect slightly *before* it hit the - // wall so that the effect doesn't sort into the wall itself. - void Interpolate(const Vector3d &from,const Vector3d &to,float offset) - { - x = to.x-from.x; - y = to.y-from.y; - z = to.z-from.z; - float d = sqrtf( x*x + y*y + z*z ); - float recip = 1.0f / d; - x*=recip; - y*=recip; - z*=recip; // normalize vector - d+=offset; // shift along ray - x = x*d + from.x; - y = y*d + from.y; - z = z*d + from.z; - }; - - bool BinaryEqual(const Vector3d &p) const - { - const int *source = (const int *) &x; - const int *dest = (const int *) &p.x; - - if ( source[0] == dest[0] && - source[1] == dest[1] && - source[2] == dest[2] ) return true; - - return false; - }; - - /*bool BinaryEqual(const Vector3d &p) const - { - if ( x == p.x && y == p.y && z == p.z ) return true; - return false; - } - */ - - - -/** Computes the reflection vector between two vectors.*/ - void Reflection(const Vector3d &a,const Vector3d &b)// compute reflection vector. - { - Vector3d c; - Vector3d d; - - float dot = a.Dot(b) * 2.0f; - - c = b * dot; - - d = c - a; - - x = -d.x; - y = -d.y; - z = -d.z; - }; - - void AngleAxis(float angle,const Vector3d& axis) - { - x = axis.x*angle; - y = axis.y*angle; - z = axis.z*angle; - }; - - float Length(void) const // length of vector. - { - return float(sqrt( x*x + y*y + z*z )); - }; - - - float ComputePlane(const Vector3d &A, - const Vector3d &B, - const Vector3d &C) - { - float vx,vy,vz,wx,wy,wz,vw_x,vw_y,vw_z,mag; - - vx = (B.x - C.x); - vy = (B.y - C.y); - vz = (B.z - C.z); - - wx = (A.x - B.x); - wy = (A.y - B.y); - wz = (A.z - B.z); - - vw_x = vy * wz - vz * wy; - vw_y = vz * wx - vx * wz; - vw_z = vx * wy - vy * wx; - - mag = sqrtf((vw_x * vw_x) + (vw_y * vw_y) + (vw_z * vw_z)); - - if ( mag < 0.000001f ) - { - mag = 0; - } - else - { - mag = 1.0f/mag; - } - - x = vw_x * mag; - y = vw_y * mag; - z = vw_z * mag; - - - float D = 0.0f - ((x*A.x)+(y*A.y)+(z*A.z)); - - return D; - } - - - float FastLength(void) const // length of vector. - { - return float(sqrtf( x*x + y*y + z*z )); - }; - - - float FasterLength(void) const // length of vector. - { - return float(sqrtf( x*x + y*y + z*z )); - }; - - float Length2(void) const // squared distance, prior to square root. - { - float l2 = x*x+y*y+z*z; - return l2; - }; - - float Distance(const Vector3d &a) const // distance between two points. - { - Vector3d d(a.x-x,a.y-y,a.z-z); - return d.Length(); - } - - float FastDistance(const Vector3d &a) const // distance between two points. - { - Vector3d d(a.x-x,a.y-y,a.z-z); - return d.FastLength(); - } - - float FasterDistance(const Vector3d &a) const // distance between two points. - { - Vector3d d(a.x-x,a.y-y,a.z-z); - return d.FasterLength(); - } - - - float DistanceXY(const Vector3d &a) const - { - float dx = a.x - x; - float dy = a.y - y; - float dist = dx*dx + dy*dy; - return dist; - } - - float Distance2(const Vector3d &a) const // squared distance. - { - float dx = a.x - x; - float dy = a.y - y; - float dz = a.z - z; - return dx*dx + dy*dy + dz*dz; - }; - - float Partial(const Vector3d &p) const - { - return (x*p.y) - (p.x*y); - } - - float Area(const Vector3d &p1,const Vector3d &p2) const - { - float A = Partial(p1); - A+= p1.Partial(p2); - A+= p2.Partial(*this); - return A*0.5f; - } - - inline float Normalize(void) // normalize to a unit vector, returns distance. - { - float d = sqrtf( static_cast< float >( x*x + y*y + z*z ) ); - if ( d > 0 ) - { - float r = 1.0f / d; - x *= r; - y *= r; - z *= r; - } - else - { - x = y = z = 1; - } - return d; - }; - - inline float FastNormalize(void) // normalize to a unit vector, returns distance. - { - float d = sqrt( static_cast< float >( x*x + y*y + z*z ) ); - if ( d > 0 ) - { - float r = 1.0f / d; - x *= r; - y *= r; - z *= r; - } - else - { - x = y = z = 1; - } - return d; - }; - - inline float FasterNormalize(void) // normalize to a unit vector, returns distance. - { - float d = sqrtf( static_cast< float >( x*x + y*y + z*z ) ); - if ( d > 0 ) - { - float r = 1.0f / d; - x *= r; - y *= r; - z *= r; - } - else - { - x = y = z = 1; - } - return d; - }; - - - - - float Dot(const Vector3d &a) const // computes dot product. - { - return (x * a.x + y * a.y + z * a.z ); - }; - - - Vector3d Cross( const Vector3d& other ) const - { - Vector3d result( y*other.z - z*other.y, z*other.x - x*other.z, x*other.y - y*other.x ); - - return result; - } - - void Cross(const Vector3d &a,const Vector3d &b) // cross two vectors result in this one. - { - x = a.y*b.z - a.z*b.y; - y = a.z*b.x - a.x*b.z; - z = a.x*b.y - a.y*b.x; - }; - - /******************************************/ - // Check if next edge (b to c) turns inward - // - // Edge from a to b is already in face - // Edge from b to c is being considered for addition to face - /******************************************/ - bool Concave(const Vector3d& a,const Vector3d& b) - { - float vx,vy,vz,wx,wy,wz,vw_x,vw_y,vw_z,mag,nx,ny,nz,mag_a,mag_b; - - wx = b.x - a.x; - wy = b.y - a.y; - wz = b.z - a.z; - - mag_a = (float) sqrtf((wx * wx) + (wy * wy) + (wz * wz)); - - vx = x - b.x; - vy = y - b.y; - vz = z - b.z; - - mag_b = (float) sqrtf((vx * vx) + (vy * vy) + (vz * vz)); - - vw_x = (vy * wz) - (vz * wy); - vw_y = (vz * wx) - (vx * wz); - vw_z = (vx * wy) - (vy * wx); - - mag = (float) sqrtf((vw_x * vw_x) + (vw_y * vw_y) + (vw_z * vw_z)); - - // Check magnitude of cross product, which is a sine function - // i.e., mag (a x b) = mag (a) * mag (b) * sin (theta); - // If sin (theta) small, then angle between edges is very close to - // 180, which we may want to call a concavity. Setting the - // CONCAVITY_TOLERANCE value greater than about 0.01 MAY cause - // face consolidation to get stuck on particular face. Most meshes - // convert properly with a value of 0.0 - - if (mag/(mag_a*mag_b) <= 0.0f ) return true; - - mag = 1.0f / mag; - - nx = vw_x * mag; - ny = vw_y * mag; - nz = vw_z * mag; - - // Dot product of tri normal with cross product result will - // yield positive number if edges are convex (+1.0 if two tris - // are coplanar), negative number if edges are concave (-1.0 if - // two tris are coplanar.) - - mag = ( x * nx) + ( y * ny) + ( z * nz); - - if (mag > 0.0f ) return false; - - return(true); - }; - - bool PointTestXY(const Vector3d &i,const Vector3d &j) const - { - if (((( i.y <= y ) && ( y < j.y )) || - (( j.y <= y ) && ( y < i.y ))) && - ( x < (j.x - i.x) * (y - i.y) / (j.y - i.y) + i.x)) return true; - return false; - } - - // test to see if this point is inside the triangle specified by - // these three points on the X/Y plane. - bool PointInTriXY(const Vector3d &p1, - const Vector3d &p2, - const Vector3d &p3) const - { - float ax = p3.x - p2.x; - float ay = p3.y - p2.y; - float bx = p1.x - p3.x; - float by = p1.y - p3.y; - float cx = p2.x - p1.x; - float cy = p2.y - p1.y; - float apx = x - p1.x; - float apy = y - p1.y; - float bpx = x - p2.x; - float bpy = y - p2.y; - float cpx = x - p3.x; - float cpy = y - p3.y; - - float aCROSSbp = ax*bpy - ay*bpx; - float cCROSSap = cx*apy - cy*apx; - float bCROSScp = bx*cpy - by*cpx; - - return ((aCROSSbp >= 0.0f) && (bCROSScp >= 0.0f) && (cCROSSap >= 0.0f)); - }; - - // test to see if this point is inside the triangle specified by - // these three points on the X/Y plane. - bool PointInTriYZ(const Vector3d &p1, - const Vector3d &p2, - const Vector3d &p3) const - { - float ay = p3.y - p2.y; - float az = p3.z - p2.z; - float by = p1.y - p3.y; - float bz = p1.z - p3.z; - float cy = p2.y - p1.y; - float cz = p2.z - p1.z; - float apy = y - p1.y; - float apz = z - p1.z; - float bpy = y - p2.y; - float bpz = z - p2.z; - float cpy = y - p3.y; - float cpz = z - p3.z; - - float aCROSSbp = ay*bpz - az*bpy; - float cCROSSap = cy*apz - cz*apy; - float bCROSScp = by*cpz - bz*cpy; - - return ((aCROSSbp >= 0.0f) && (bCROSScp >= 0.0f) && (cCROSSap >= 0.0f)); - }; - - - // test to see if this point is inside the triangle specified by - // these three points on the X/Y plane. - bool PointInTriXZ(const Vector3d &p1, - const Vector3d &p2, - const Vector3d &p3) const - { - float az = p3.z - p2.z; - float ax = p3.x - p2.x; - float bz = p1.z - p3.z; - float bx = p1.x - p3.x; - float cz = p2.z - p1.z; - float cx = p2.x - p1.x; - float apz = z - p1.z; - float apx = x - p1.x; - float bpz = z - p2.z; - float bpx = x - p2.x; - float cpz = z - p3.z; - float cpx = x - p3.x; - - float aCROSSbp = az*bpx - ax*bpz; - float cCROSSap = cz*apx - cx*apz; - float bCROSScp = bz*cpx - bx*cpz; - - return ((aCROSSbp >= 0.0f) && (bCROSScp >= 0.0f) && (cCROSSap >= 0.0f)); - }; - - // Given a point and a line (defined by two points), compute the closest point - // in the line. (The line is treated as infinitely long.) - void NearestPointInLine(const Vector3d &point, - const Vector3d &line0, - const Vector3d &line1) - { - Vector3d &nearestPoint = *this; - Vector3d lineDelta = line1 - line0; - - // Handle degenerate lines - if ( lineDelta == Vector3d(0, 0, 0) ) - { - nearestPoint = line0; - } - else - { - float delta = (point-line0).Dot(lineDelta) / (lineDelta).Dot(lineDelta); - nearestPoint = line0 + lineDelta*delta; - } - } - - // Given a point and a line segment (defined by two points), compute the closest point - // in the line. Cap the point at the endpoints of the line segment. - void NearestPointInLineSegment(const Vector3d &point, - const Vector3d &line0, - const Vector3d &line1) - { - Vector3d &nearestPoint = *this; - Vector3d lineDelta = line1 - line0; - - // Handle degenerate lines - if ( lineDelta == Vector3d(0, 0, 0) ) - { - nearestPoint = line0; - } - else - { - float delta = (point-line0).Dot(lineDelta) / (lineDelta).Dot(lineDelta); - - // Clamp the point to conform to the segment's endpoints - if ( delta < 0 ) - delta = 0; - else if ( delta > 1 ) - delta = 1; - - nearestPoint = line0 + lineDelta*delta; - } - } - - // Given a point and a plane (defined by three points), compute the closest point - // in the plane. (The plane is unbounded.) - void NearestPointInPlane(const Vector3d &point, - const Vector3d &triangle0, - const Vector3d &triangle1, - const Vector3d &triangle2) - { - Vector3d &nearestPoint = *this; - Vector3d lineDelta0 = triangle1 - triangle0; - Vector3d lineDelta1 = triangle2 - triangle0; - Vector3d pointDelta = point - triangle0; - Vector3d normal; - - // Get the normal of the polygon (doesn't have to be a unit vector) - normal.Cross(lineDelta0, lineDelta1); - - float delta = normal.Dot(pointDelta) / normal.Dot(normal); - nearestPoint = point - normal*delta; - } - - // Given a point and a plane (defined by a coplanar point and a normal), compute the closest point - // in the plane. (The plane is unbounded.) - void NearestPointInPlane(const Vector3d &point, - const Vector3d &planePoint, - const Vector3d &planeNormal) - { - Vector3d &nearestPoint = *this; - Vector3d pointDelta = point - planePoint; - - float delta = planeNormal.Dot(pointDelta) / planeNormal.Dot(planeNormal); - nearestPoint = point - planeNormal*delta; - } - - // Given a point and a triangle (defined by three points), compute the closest point - // in the triangle. Clamp the point so it's confined to the area of the triangle. - void NearestPointInTriangle(const Vector3d &point, - const Vector3d &triangle0, - const Vector3d &triangle1, - const Vector3d &triangle2) - { - static const Vector3d zeroVector(0, 0, 0); - - Vector3d &nearestPoint = *this; - - Vector3d lineDelta0 = triangle1 - triangle0; - Vector3d lineDelta1 = triangle2 - triangle0; - - // Handle degenerate triangles - if ( (lineDelta0 == zeroVector) || (lineDelta1 == zeroVector) ) - { - nearestPoint.NearestPointInLineSegment(point, triangle1, triangle2); - } - else if ( lineDelta0 == lineDelta1 ) - { - nearestPoint.NearestPointInLineSegment(point, triangle0, triangle1); - } - - else - { - Vector3d axis[3]; - axis[0].NearestPointInLine(triangle0, triangle1, triangle2); - axis[1].NearestPointInLine(triangle1, triangle0, triangle2); - axis[2].NearestPointInLine(triangle2, triangle0, triangle1); - - float axisDot[3]; - axisDot[0] = (triangle0-axis[0]).Dot(point-axis[0]); - axisDot[1] = (triangle1-axis[1]).Dot(point-axis[1]); - axisDot[2] = (triangle2-axis[2]).Dot(point-axis[2]); - - bool bForce = true; - float bestMagnitude2 = 0; - float closeMagnitude2; - Vector3d closePoint; - - if ( axisDot[0] < 0 ) - { - closePoint.NearestPointInLineSegment(point, triangle1, triangle2); - closeMagnitude2 = point.Distance2(closePoint); - if ( bForce || (bestMagnitude2 > closeMagnitude2) ) - { - bForce = false; - bestMagnitude2 = closeMagnitude2; - nearestPoint = closePoint; - } - } - if ( axisDot[1] < 0 ) - { - closePoint.NearestPointInLineSegment(point, triangle0, triangle2); - closeMagnitude2 = point.Distance2(closePoint); - if ( bForce || (bestMagnitude2 > closeMagnitude2) ) - { - bForce = false; - bestMagnitude2 = closeMagnitude2; - nearestPoint = closePoint; - } - } - if ( axisDot[2] < 0 ) - { - closePoint.NearestPointInLineSegment(point, triangle0, triangle1); - closeMagnitude2 = point.Distance2(closePoint); - if ( bForce || (bestMagnitude2 > closeMagnitude2) ) - { - bForce = false; - bestMagnitude2 = closeMagnitude2; - nearestPoint = closePoint; - } - } - - // If bForce is true at this point, it means the nearest point lies - // inside the triangle; use the nearest-point-on-a-plane equation - if ( bForce ) - { - Vector3d normal; - - // Get the normal of the polygon (doesn't have to be a unit vector) - normal.Cross(lineDelta0, lineDelta1); - - Vector3d pointDelta = point - triangle0; - float delta = normal.Dot(pointDelta) / normal.Dot(normal); - - nearestPoint = point - normal*delta; - } - } - } - - -//private: - - float x; - float y; - float z; -}; - - -class Vector2d -{ -public: - Vector2d(void) { }; // null constructor, does not inialize point. - - Vector2d(const Vector2d &a) // constructor copies existing vector. - { - x = a.x; - y = a.y; - }; - - Vector2d(const float *t) - { - x = t[0]; - y = t[1]; - }; - - - Vector2d(float a,float b) // construct with initial point. - { - x = a; - y = b; - }; - - const float* Ptr() const { return &x; } - float* Ptr() { return &x; } - - Vector2d & operator+=(const Vector2d &a) // += operator. - { - x+=a.x; - y+=a.y; - return *this; - }; - - Vector2d & operator-=(const Vector2d &a) - { - x-=a.x; - y-=a.y; - return *this; - }; - - Vector2d & operator*=(const Vector2d &a) - { - x*=a.x; - y*=a.y; - return *this; - }; - - Vector2d & operator/=(const Vector2d &a) - { - x/=a.x; - y/=a.y; - return *this; - }; - - bool operator==(const Vector2d &a) const - { - if ( a.x == x && a.y == y ) return true; - return false; - }; - - bool operator!=(const Vector2d &a) const - { - if ( a.x != x || a.y != y ) return true; - return false; - }; - - Vector2d operator+(Vector2d a) const - { - a.x+=x; - a.y+=y; - return a; - }; - - Vector2d operator-(Vector2d a) const - { - a.x = x-a.x; - a.y = y-a.y; - return a; - }; - - Vector2d operator - (void) const - { - return negative(); - }; - - Vector2d operator*(Vector2d a) const - { - a.x*=x; - a.y*=y; - return a; - }; - - Vector2d operator*(float c) const - { - Vector2d a; - - a.x = x * c; - a.y = y * c; - - return a; - }; - - Vector2d operator/(Vector2d a) const - { - a.x = x/a.x; - a.y = y/a.y; - return a; - }; - - - float Dot(const Vector2d &a) const // computes dot product. - { - return (x * a.x + y * a.y ); - }; - - float GetX(void) const { return x; }; - float GetY(void) const { return y; }; - - void SetX(float t) { x = t; }; - void SetY(float t) { y = t; }; - - void Set(float a,float b) - { - x = a; - y = b; - }; - - void Zero(void) - { - x = y = 0; - }; - - Vector2d negative(void) const - { - Vector2d result; - result.x = -x; - result.y = -y; - return result; - } - - float magnitude(void) const - { - return (float) sqrtf(x * x + y * y ); - } - - float fastmagnitude(void) const - { - return (float) sqrtf(x * x + y * y ); - } - - float fastermagnitude(void) const - { - return (float) sqrtf( x * x + y * y ); - } - - void Reflection(Vector2d &a,Vector2d &b); // compute reflection vector. - - float Length(void) const // length of vector. - { - return float(sqrtf( x*x + y*y )); - }; - - float FastLength(void) const // length of vector. - { - return float(sqrtf( x*x + y*y )); - }; - - float FasterLength(void) const // length of vector. - { - return float(sqrtf( x*x + y*y )); - }; - - float Length2(void) // squared distance, prior to square root. - { - return x*x+y*y; - } - - float Distance(const Vector2d &a) const // distance between two points. - { - float dx = a.x - x; - float dy = a.y - y; - float d = dx*dx+dy*dy; - return sqrtf(d); - }; - - float FastDistance(const Vector2d &a) const // distance between two points. - { - float dx = a.x - x; - float dy = a.y - y; - float d = dx*dx+dy*dy; - return sqrtf(d); - }; - - float FasterDistance(const Vector2d &a) const // distance between two points. - { - float dx = a.x - x; - float dy = a.y - y; - float d = dx*dx+dy*dy; - return sqrtf(d); - }; - - float Distance2(Vector2d &a) // squared distance. - { - float dx = a.x - x; - float dy = a.y - y; - return dx*dx + dy *dy; - }; - - void Lerp(const Vector2d& from,const Vector2d& to,float slerp) - { - x = ((to.x - from.x)*slerp) + from.x; - y = ((to.y - from.y)*slerp) + from.y; - }; - - - void Cross(const Vector2d &a,const Vector2d &b) // cross two vectors result in this one. - { - x = a.y*b.x - a.x*b.y; - y = a.x*b.x - a.x*b.x; - }; - - float Normalize(void) // normalize to a unit vector, returns distance. - { - float l = Length(); - if ( l != 0 ) - { - l = float( 1 ) / l; - x*=l; - y*=l; - } - else - { - x = y = 0; - } - return l; - }; - - float FastNormalize(void) // normalize to a unit vector, returns distance. - { - float l = FastLength(); - if ( l != 0 ) - { - l = float( 1 ) / l; - x*=l; - y*=l; - } - else - { - x = y = 0; - } - return l; - }; - - float FasterNormalize(void) // normalize to a unit vector, returns distance. - { - float l = FasterLength(); - if ( l != 0 ) - { - l = float( 1 ) / l; - x*=l; - y*=l; - } - else - { - x = y = 0; - } - return l; - }; - - - float x; - float y; -}; - -class Line -{ -public: - Line(const Vector3d &from,const Vector3d &to) - { - mP1 = from; - mP2 = to; - }; - // JWR Test for the intersection of two lines. - - bool Intersect(const Line& src,Vector3d §); -private: - Vector3d mP1; - Vector3d mP2; - -}; - - -typedef std::vector< Vector3d > Vector3dVector; -typedef std::vector< Vector2d > Vector2dVector; - -inline Vector3d operator * (float s, const Vector3d &v ) -{ - Vector3d Scaled(v.x*s, v.y*s, v.z*s); - return(Scaled); -} - -inline Vector2d operator * (float s, const Vector2d &v ) - { - Vector2d Scaled(v.x*s, v.y*s); - return(Scaled); - } - -} - -#endif diff --git a/extern/bullet/src/Extras/ConvexDecomposition/cd_wavefront.cpp b/extern/bullet/src/Extras/ConvexDecomposition/cd_wavefront.cpp deleted file mode 100644 index 54e8bdf68e63..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/cd_wavefront.cpp +++ /dev/null @@ -1,860 +0,0 @@ -#include -#include -#include -#include -#include - -/*---------------------------------------------------------------------- - Copyright (c) 2004 Open Dynamics Framework Group - www.physicstools.org - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are permitted provided - that the following conditions are met: - - Redistributions of source code must retain the above copyright notice, this list of conditions - and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - Neither the name of the Open Dynamics Framework Group nor the names of its contributors may - be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER - IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -// http://codesuppository.blogspot.com -// -// mailto: jratcliff@infiniplex.net -// -// http://www.amillionpixels.us -// -#include "float_math.h" - -#include "cd_wavefront.h" - - -using namespace ConvexDecomposition; - -/*---------------------------------------------------------------------- - Copyright (c) 2004 Open Dynamics Framework Group - www.physicstools.org - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are permitted provided - that the following conditions are met: - - Redistributions of source code must retain the above copyright notice, this list of conditions - and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - Neither the name of the Open Dynamics Framework Group nor the names of its contributors may - be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER - IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -#include - -namespace ConvexDecomposition -{ - -typedef std::vector< int > IntVector; -typedef std::vector< float > FloatVector; - -#if defined(__APPLE__) || defined(__CELLOS_LV2__) -#define stricmp(a, b) strcasecmp((a), (b)) -#endif - -/*******************************************************************/ -/******************** InParser.h ********************************/ -/*******************************************************************/ -class InPlaceParserInterface -{ -public: - virtual ~InPlaceParserInterface () {} ; - - virtual int ParseLine(int lineno,int argc,const char **argv) =0; // return TRUE to continue parsing, return FALSE to abort parsing process -}; - -enum SeparatorType -{ - ST_DATA, // is data - ST_HARD, // is a hard separator - ST_SOFT, // is a soft separator - ST_EOS // is a comment symbol, and everything past this character should be ignored -}; - -class InPlaceParser -{ -public: - InPlaceParser(void) - { - Init(); - } - - InPlaceParser(char *data,int len) - { - Init(); - SetSourceData(data,len); - } - - InPlaceParser(const char *fname) - { - Init(); - SetFile(fname); - } - - ~InPlaceParser(void); - - void Init(void) - { - mQuoteChar = 34; - mData = 0; - mLen = 0; - mMyAlloc = false; - for (int i=0; i<256; i++) - { - mHard[i] = ST_DATA; - mHardString[i*2] = i; - mHardString[i*2+1] = 0; - } - mHard[0] = ST_EOS; - mHard[32] = ST_SOFT; - mHard[9] = ST_SOFT; - mHard[13] = ST_SOFT; - mHard[10] = ST_SOFT; - } - - void SetFile(const char *fname); // use this file as source data to parse. - - void SetSourceData(char *data,int len) - { - mData = data; - mLen = len; - mMyAlloc = false; - }; - - int Parse(InPlaceParserInterface *callback); // returns true if entire file was parsed, false if it aborted for some reason - - int ProcessLine(int lineno,char *line,InPlaceParserInterface *callback); - - const char ** GetArglist(char *source,int &count); // convert source string into an arg list, this is a destructive parse. - - void SetHardSeparator(char c) // add a hard separator - { - mHard[(int)c] = ST_HARD; - } - - void SetHard(char c) // add a hard separator - { - mHard[(int)c] = ST_HARD; - } - - - void SetCommentSymbol(char c) // comment character, treated as 'end of string' - { - mHard[(int)c] = ST_EOS; - } - - void ClearHardSeparator(char c) - { - mHard[(int)c] = ST_DATA; - } - - - void DefaultSymbols(void); // set up default symbols for hard seperator and comment symbol of the '#' character. - - bool EOS(char c) - { - if ( mHard[(int)c] == ST_EOS ) - { - return true; - } - return false; - } - - void SetQuoteChar(char c) - { - mQuoteChar = c; - } - -private: - - - inline char * AddHard(int &argc,const char **argv,char *foo); - inline bool IsHard(char c); - inline char * SkipSpaces(char *foo); - inline bool IsWhiteSpace(char c); - inline bool IsNonSeparator(char c); // non seperator,neither hard nor soft - - bool mMyAlloc; // whether or not *I* allocated the buffer and am responsible for deleting it. - char *mData; // ascii data to parse. - int mLen; // length of data - SeparatorType mHard[256]; - char mHardString[256*2]; - char mQuoteChar; -}; - -/*******************************************************************/ -/******************** InParser.cpp ********************************/ -/*******************************************************************/ -void InPlaceParser::SetFile(const char *fname) -{ - if ( mMyAlloc ) - { - free(mData); - } - mData = 0; - mLen = 0; - mMyAlloc = false; - - - FILE *fph = fopen(fname,"rb"); - if ( fph ) - { - fseek(fph,0L,SEEK_END); - mLen = ftell(fph); - fseek(fph,0L,SEEK_SET); - if ( mLen ) - { - mData = (char *) malloc(sizeof(char)*(mLen+1)); - int ok = fread(mData, mLen, 1, fph); - if ( !ok ) - { - free(mData); - mData = 0; - } - else - { - mData[mLen] = 0; // zero byte terminate end of file marker. - mMyAlloc = true; - } - } - fclose(fph); - } -} - -InPlaceParser::~InPlaceParser(void) -{ - if ( mMyAlloc ) - { - free(mData); - } -} - -#define MAXARGS 512 - -bool InPlaceParser::IsHard(char c) -{ - return mHard[(int)c] == ST_HARD; -} - -char * InPlaceParser::AddHard(int &argc,const char **argv,char *foo) -{ - while ( IsHard(*foo) ) - { - const char *hard = &mHardString[*foo*2]; - if ( argc < MAXARGS ) - { - argv[argc++] = hard; - } - foo++; - } - return foo; -} - -bool InPlaceParser::IsWhiteSpace(char c) -{ - return mHard[(int)c] == ST_SOFT; -} - -char * InPlaceParser::SkipSpaces(char *foo) -{ - while ( !EOS(*foo) && IsWhiteSpace(*foo) ) foo++; - return foo; -} - -bool InPlaceParser::IsNonSeparator(char c) -{ - if ( !IsHard(c) && !IsWhiteSpace(c) && c != 0 ) return true; - return false; -} - - -int InPlaceParser::ProcessLine(int lineno,char *line,InPlaceParserInterface *callback) -{ - int ret = 0; - - const char *argv[MAXARGS]; - int argc = 0; - - char *foo = line; - - while ( !EOS(*foo) && argc < MAXARGS ) - { - - foo = SkipSpaces(foo); // skip any leading spaces - - if ( EOS(*foo) ) break; - - if ( *foo == mQuoteChar ) // if it is an open quote - { - foo++; - if ( argc < MAXARGS ) - { - argv[argc++] = foo; - } - while ( !EOS(*foo) && *foo != mQuoteChar ) foo++; - if ( !EOS(*foo) ) - { - *foo = 0; // replace close quote with zero byte EOS - foo++; - } - } - else - { - - foo = AddHard(argc,argv,foo); // add any hard separators, skip any spaces - - if ( IsNonSeparator(*foo) ) // add non-hard argument. - { - bool quote = false; - if ( *foo == mQuoteChar ) - { - foo++; - quote = true; - } - - if ( argc < MAXARGS ) - { - argv[argc++] = foo; - } - - if ( quote ) - { - while (*foo && *foo != mQuoteChar ) foo++; - if ( *foo ) *foo = 32; - } - - // continue..until we hit an eos .. - while ( !EOS(*foo) ) // until we hit EOS - { - if ( IsWhiteSpace(*foo) ) // if we hit a space, stomp a zero byte, and exit - { - *foo = 0; - foo++; - break; - } - else if ( IsHard(*foo) ) // if we hit a hard separator, stomp a zero byte and store the hard separator argument - { - const char *hard = &mHardString[*foo*2]; - *foo = 0; - if ( argc < MAXARGS ) - { - argv[argc++] = hard; - } - foo++; - break; - } - foo++; - } // end of while loop... - } - } - } - - if ( argc ) - { - ret = callback->ParseLine(lineno, argc, argv ); - } - - return ret; -} - -int InPlaceParser::Parse(InPlaceParserInterface *callback) // returns true if entire file was parsed, false if it aborted for some reason -{ - assert( callback ); - if ( !mData ) return 0; - - int ret = 0; - - int lineno = 0; - - char *foo = mData; - char *begin = foo; - - - while ( *foo ) - { - if ( *foo == 10 || *foo == 13 ) - { - lineno++; - *foo = 0; - - if ( *begin ) // if there is any data to parse at all... - { - int v = ProcessLine(lineno,begin,callback); - if ( v ) ret = v; - } - - foo++; - if ( *foo == 10 ) foo++; // skip line feed, if it is in the carraige-return line-feed format... - begin = foo; - } - else - { - foo++; - } - } - - lineno++; // lasst line. - - int v = ProcessLine(lineno,begin,callback); - if ( v ) ret = v; - return ret; -} - - -void InPlaceParser::DefaultSymbols(void) -{ - SetHardSeparator(','); - SetHardSeparator('('); - SetHardSeparator(')'); - SetHardSeparator('='); - SetHardSeparator('['); - SetHardSeparator(']'); - SetHardSeparator('{'); - SetHardSeparator('}'); - SetCommentSymbol('#'); -} - - -const char ** InPlaceParser::GetArglist(char *line,int &count) // convert source string into an arg list, this is a destructive parse. -{ - const char **ret = 0; - - const char *argv[MAXARGS]; - int argc = 0; - - char *foo = line; - - while ( !EOS(*foo) && argc < MAXARGS ) - { - - foo = SkipSpaces(foo); // skip any leading spaces - - if ( EOS(*foo) ) break; - - if ( *foo == mQuoteChar ) // if it is an open quote - { - foo++; - if ( argc < MAXARGS ) - { - argv[argc++] = foo; - } - while ( !EOS(*foo) && *foo != mQuoteChar ) foo++; - if ( !EOS(*foo) ) - { - *foo = 0; // replace close quote with zero byte EOS - foo++; - } - } - else - { - - foo = AddHard(argc,argv,foo); // add any hard separators, skip any spaces - - if ( IsNonSeparator(*foo) ) // add non-hard argument. - { - bool quote = false; - if ( *foo == mQuoteChar ) - { - foo++; - quote = true; - } - - if ( argc < MAXARGS ) - { - argv[argc++] = foo; - } - - if ( quote ) - { - while (*foo && *foo != mQuoteChar ) foo++; - if ( *foo ) *foo = 32; - } - - // continue..until we hit an eos .. - while ( !EOS(*foo) ) // until we hit EOS - { - if ( IsWhiteSpace(*foo) ) // if we hit a space, stomp a zero byte, and exit - { - *foo = 0; - foo++; - break; - } - else if ( IsHard(*foo) ) // if we hit a hard separator, stomp a zero byte and store the hard separator argument - { - const char *hard = &mHardString[*foo*2]; - *foo = 0; - if ( argc < MAXARGS ) - { - argv[argc++] = hard; - } - foo++; - break; - } - foo++; - } // end of while loop... - } - } - } - - count = argc; - if ( argc ) - { - ret = argv; - } - - return ret; -} - -/*******************************************************************/ -/******************** Geometry.h ********************************/ -/*******************************************************************/ - -class GeometryVertex -{ -public: - float mPos[3]; - float mNormal[3]; - float mTexel[2]; -}; - - -class GeometryInterface -{ -public: - - virtual void NodeTriangle(const GeometryVertex *v1,const GeometryVertex *v2,const GeometryVertex *v3) {} - - virtual ~GeometryInterface () {} -}; - - -/*******************************************************************/ -/******************** Obj.h ********************************/ -/*******************************************************************/ - - -class OBJ : public InPlaceParserInterface -{ -public: - int LoadMesh(const char *fname,GeometryInterface *callback); - int ParseLine(int lineno,int argc,const char **argv); // return TRUE to continue parsing, return FALSE to abort parsing process -private: - - void getVertex(GeometryVertex &v,const char *face) const; - - FloatVector mVerts; - FloatVector mTexels; - FloatVector mNormals; - - GeometryInterface *mCallback; -}; - - -/*******************************************************************/ -/******************** Obj.cpp ********************************/ -/*******************************************************************/ - -int OBJ::LoadMesh(const char *fname,GeometryInterface *iface) -{ - int ret = 0; - - mVerts.clear(); - mTexels.clear(); - mNormals.clear(); - - mCallback = iface; - - InPlaceParser ipp(fname); - - ipp.Parse(this); - - - return ret; -} - -//static const char * GetArg(const char **argv,int i,int argc) -//{ - // const char * ret = 0; - // if ( i < argc ) ret = argv[i]; - // return ret; -//} - -void OBJ::getVertex(GeometryVertex &v,const char *face) const -{ - v.mPos[0] = 0; - v.mPos[1] = 0; - v.mPos[2] = 0; - - v.mTexel[0] = 0; - v.mTexel[1] = 0; - - v.mNormal[0] = 0; - v.mNormal[1] = 1; - v.mNormal[2] = 0; - - int index = atoi( face )-1; - - const char *texel = strstr(face,"/"); - - if ( texel ) - { - int tindex = atoi( texel+1) - 1; - - if ( tindex >=0 && tindex < (int)(mTexels.size()/2) ) - { - const float *t = &mTexels[tindex*2]; - - v.mTexel[0] = t[0]; - v.mTexel[1] = t[1]; - - } - - const char *normal = strstr(texel+1,"/"); - if ( normal ) - { - int nindex = atoi( normal+1 ) - 1; - - if (nindex >= 0 && nindex < (int)(mNormals.size()/3) ) - { - const float *n = &mNormals[nindex*3]; - - v.mNormal[0] = n[0]; - v.mNormal[1] = n[1]; - v.mNormal[2] = n[2]; - } - } - } - - if ( index >= 0 && index < (int)(mVerts.size()/3) ) - { - - const float *p = &mVerts[index*3]; - - v.mPos[0] = p[0]; - v.mPos[1] = p[1]; - v.mPos[2] = p[2]; - } - -} - -int OBJ::ParseLine(int lineno,int argc,const char **argv) // return TRUE to continue parsing, return FALSE to abort parsing process -{ - int ret = 0; - - if ( argc >= 1 ) - { - const char *foo = argv[0]; - if ( *foo != '#' ) - { - if ( strcmp(argv[0],"v") == 0 && argc == 4 ) - - //if ( stricmp(argv[0],"v") == 0 && argc == 4 ) - { - float vx = (float) atof( argv[1] ); - float vy = (float) atof( argv[2] ); - float vz = (float) atof( argv[3] ); - mVerts.push_back(vx); - mVerts.push_back(vy); - mVerts.push_back(vz); - } - else if ( strcmp(argv[0],"vt") == 0 && argc == 3 ) - - // else if ( stricmp(argv[0],"vt") == 0 && argc == 3 ) - { - float tx = (float) atof( argv[1] ); - float ty = (float) atof( argv[2] ); - mTexels.push_back(tx); - mTexels.push_back(ty); - } - // else if ( stricmp(argv[0],"vn") == 0 && argc == 4 ) - - else if ( strcmp(argv[0],"vn") == 0 && argc == 4 ) - { - float normalx = (float) atof(argv[1]); - float normaly = (float) atof(argv[2]); - float normalz = (float) atof(argv[3]); - mNormals.push_back(normalx); - mNormals.push_back(normaly); - mNormals.push_back(normalz); - } -// else if ( stricmp(argv[0],"f") == 0 && argc >= 4 ) - - else if ( strcmp(argv[0],"f") == 0 && argc >= 4 ) - { - GeometryVertex v[32]; - - int vcount = argc-1; - - for (int i=1; i p1( v[0].mPos ); - Vector3d p2( v[1].mPos ); - Vector3d p3( v[2].mPos ); - - Vector3d n; - n.ComputeNormal(p3,p2,p1); - - for (int i=0; iNodeTriangle(&v[0],&v[1],&v[2]); - - if ( vcount >=3 ) // do the fan - { - for (int i=2; i<(vcount-1); i++) - { - mCallback->NodeTriangle(&v[0],&v[i],&v[i+1]); - } - } - - } - } - } - - return ret; -} - - - - -class BuildMesh : public GeometryInterface -{ -public: - - int getIndex(const float *p) - { - - int vcount = mVertices.size()/3; - - if(vcount>0) - { - //New MS STL library checks indices in debug build, so zero causes an assert if it is empty. - const float *v = &mVertices[0]; - - for (int i=0; imPos) ); - mIndices.push_back( getIndex(v2->mPos) ); - mIndices.push_back( getIndex(v3->mPos) ); - } - - const FloatVector& GetVertices(void) const { return mVertices; }; - const IntVector& GetIndices(void) const { return mIndices; }; - -private: - FloatVector mVertices; - IntVector mIndices; -}; - - -WavefrontObj::WavefrontObj(void) -{ - mVertexCount = 0; - mTriCount = 0; - mIndices = 0; - mVertices = 0; -} - -WavefrontObj::~WavefrontObj(void) -{ - delete [] mIndices; - delete [] mVertices; -} - -unsigned int WavefrontObj::loadObj(const char *fname) // load a wavefront obj returns number of triangles that were loaded. Data is persists until the class is destructed. -{ - - unsigned int ret = 0; - - delete [] mVertices; - mVertices = 0; - delete [] mIndices; - mIndices = 0; - mVertexCount = 0; - mTriCount = 0; - - - BuildMesh bm; - - OBJ obj; - - obj.LoadMesh(fname,&bm); - - - const FloatVector &vlist = bm.GetVertices(); - const IntVector &indices = bm.GetIndices(); - if ( vlist.size() ) - { - mVertexCount = vlist.size()/3; - mVertices = new float[mVertexCount*3]; - memcpy( mVertices, &vlist[0], sizeof(float)*mVertexCount*3 ); - mTriCount = indices.size()/3; - mIndices = new int[mTriCount*3*sizeof(int)]; - memcpy(mIndices, &indices[0], sizeof(int)*mTriCount*3); - ret = mTriCount; - } - - - return ret; -} - -} diff --git a/extern/bullet/src/Extras/ConvexDecomposition/cd_wavefront.h b/extern/bullet/src/Extras/ConvexDecomposition/cd_wavefront.h deleted file mode 100644 index ba5f90bd5505..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/cd_wavefront.h +++ /dev/null @@ -1,62 +0,0 @@ -#ifndef CD_WAVEFRONT_OBJ_H - - -#define CD_WAVEFRONT_OBJ_H - - -/*---------------------------------------------------------------------- - Copyright (c) 2004 Open Dynamics Framework Group - www.physicstools.org - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are permitted provided - that the following conditions are met: - - Redistributions of source code must retain the above copyright notice, this list of conditions - and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - Neither the name of the Open Dynamics Framework Group nor the names of its contributors may - be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER - IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -// http://codesuppository.blogspot.com -// -// mailto: jratcliff@infiniplex.net -// -// http://www.amillionpixels.us -// - - -namespace ConvexDecomposition -{ - -class WavefrontObj -{ -public: - - WavefrontObj(void); - ~WavefrontObj(void); - - unsigned int loadObj(const char *fname); // load a wavefront obj returns number of triangles that were loaded. Data is persists until the class is destructed. - - int mVertexCount; - int mTriCount; - int *mIndices; - float *mVertices; -}; - -} - -#endif diff --git a/extern/bullet/src/Extras/ConvexDecomposition/concavity.cpp b/extern/bullet/src/Extras/ConvexDecomposition/concavity.cpp deleted file mode 100644 index 5827da293845..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/concavity.cpp +++ /dev/null @@ -1,797 +0,0 @@ -#include "float_math.h" -#include -#include -#include -#include - -#include - -/*---------------------------------------------------------------------- - Copyright (c) 2004 Open Dynamics Framework Group - www.physicstools.org - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are permitted provided - that the following conditions are met: - - Redistributions of source code must retain the above copyright notice, this list of conditions - and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - Neither the name of the Open Dynamics Framework Group nor the names of its contributors may - be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER - IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -// http://codesuppository.blogspot.com -// -// mailto: jratcliff@infiniplex.net -// -// http://www.amillionpixels.us -// - -#include "concavity.h" -#include "raytri.h" -#include "bestfit.h" -#include "cd_hull.h" -#include "meshvolume.h" -#include "cd_vector.h" -#include "splitplane.h" -#include "ConvexDecomposition.h" - - -#define WSCALE 4 -#define CONCAVE_THRESH 0.05f - -namespace ConvexDecomposition -{ - -unsigned int getDebugColor(void) -{ - static unsigned int colors[8] = - { - 0xFF0000, - 0x00FF00, - 0x0000FF, - 0xFFFF00, - 0x00FFFF, - 0xFF00FF, - 0xFFFFFF, - 0xFF8040 - }; - - static int count = 0; - - count++; - - if ( count == 8 ) count = 0; - - assert( count >= 0 && count < 8 ); - - unsigned int color = colors[count]; - - return color; - -} - -class Wpoint -{ -public: - Wpoint(const Vector3d &p,float w) - { - mPoint = p; - mWeight = w; - } - - Vector3d mPoint; - float mWeight; -}; - -typedef std::vector< Wpoint > WpointVector; - - -static inline float DistToPt(const float *p,const float *plane) -{ - float x = p[0]; - float y = p[1]; - float z = p[2]; - float d = x*plane[0] + y*plane[1] + z*plane[2] + plane[3]; - return d; -} - - -static void intersect(const float *p1,const float *p2,float *split,const float *plane) -{ - - float dp1 = DistToPt(p1,plane); - - float dir[3]; - - dir[0] = p2[0] - p1[0]; - dir[1] = p2[1] - p1[1]; - dir[2] = p2[2] - p1[2]; - - float dot1 = dir[0]*plane[0] + dir[1]*plane[1] + dir[2]*plane[2]; - float dot2 = dp1 - plane[3]; - - float t = -(plane[3] + dot2 ) / dot1; - - split[0] = (dir[0]*t)+p1[0]; - split[1] = (dir[1]*t)+p1[1]; - split[2] = (dir[2]*t)+p1[2]; -} - - -class CTri -{ -public: - CTri(void) { }; - - CTri(const float *p1,const float *p2,const float *p3,unsigned int i1,unsigned int i2,unsigned int i3) - { - mProcessed = 0; - mI1 = i1; - mI2 = i2; - mI3 = i3; - - mP1.Set(p1); - mP2.Set(p2); - mP3.Set(p3); - - mPlaneD = mNormal.ComputePlane(mP1,mP2,mP3); - } - - float Facing(const CTri &t) - { - float d = mNormal.Dot(t.mNormal); - return d; - } - - // clip this line segment against this triangle. - bool clip(const Vector3d &start,Vector3d &end) const - { - Vector3d sect; - - bool hit = lineIntersectsTriangle(start.Ptr(), end.Ptr(), mP1.Ptr(), mP2.Ptr(), mP3.Ptr(), sect.Ptr() ); - - if ( hit ) - { - end = sect; - } - return hit; - } - - bool Concave(const Vector3d &p,float &distance,Vector3d &n) const - { - n.NearestPointInTriangle(p,mP1,mP2,mP3); - distance = p.Distance(n); - return true; - } - - void addTri(unsigned int *indices,unsigned int i1,unsigned int i2,unsigned int i3,unsigned int &tcount) const - { - indices[tcount*3+0] = i1; - indices[tcount*3+1] = i2; - indices[tcount*3+2] = i3; - tcount++; - } - - float getVolume(ConvexDecompInterface *callback) const - { - unsigned int indices[8*3]; - - - unsigned int tcount = 0; - - addTri(indices,0,1,2,tcount); - addTri(indices,3,4,5,tcount); - - addTri(indices,0,3,4,tcount); - addTri(indices,0,4,1,tcount); - - addTri(indices,1,4,5,tcount); - addTri(indices,1,5,2,tcount); - - addTri(indices,0,3,5,tcount); - addTri(indices,0,5,2,tcount); - - const float *vertices = mP1.Ptr(); - - if ( callback ) - { - unsigned int color = getDebugColor(); - -#if 0 - Vector3d d1 = mNear1; - Vector3d d2 = mNear2; - Vector3d d3 = mNear3; - - callback->ConvexDebugPoint(mP1.Ptr(),0.01f,0x00FF00); - callback->ConvexDebugPoint(mP2.Ptr(),0.01f,0x00FF00); - callback->ConvexDebugPoint(mP3.Ptr(),0.01f,0x00FF00); - callback->ConvexDebugPoint(d1.Ptr(),0.01f,0xFF0000); - callback->ConvexDebugPoint(d2.Ptr(),0.01f,0xFF0000); - callback->ConvexDebugPoint(d3.Ptr(),0.01f,0xFF0000); - - callback->ConvexDebugTri(mP1.Ptr(), d1.Ptr(), d1.Ptr(),0x00FF00); - callback->ConvexDebugTri(mP2.Ptr(), d2.Ptr(), d2.Ptr(),0x00FF00); - callback->ConvexDebugTri(mP3.Ptr(), d3.Ptr(), d3.Ptr(),0x00FF00); - -#else - for (unsigned int i=0; iConvexDebugTri(p1,p2,p3,color); - - } -#endif - } - - float v = computeMeshVolume(mP1.Ptr(), tcount, indices ); - - return v; - - } - - float raySect(const Vector3d &p,const Vector3d &dir,Vector3d §) const - { - float plane[4]; - - plane[0] = mNormal.x; - plane[1] = mNormal.y; - plane[2] = mNormal.z; - plane[3] = mPlaneD; - - Vector3d dest = p+dir*100000; - - intersect( p.Ptr(), dest.Ptr(), sect.Ptr(), plane ); - - return sect.Distance(p); // return the intersection distance. - - } - - float planeDistance(const Vector3d &p) const - { - float plane[4]; - - plane[0] = mNormal.x; - plane[1] = mNormal.y; - plane[2] = mNormal.z; - plane[3] = mPlaneD; - - return DistToPt( p.Ptr(), plane ); - - } - - bool samePlane(const CTri &t) const - { - const float THRESH = 0.001f; - float dd = fabsf( t.mPlaneD - mPlaneD ); - if ( dd > THRESH ) return false; - dd = fabsf( t.mNormal.x - mNormal.x ); - if ( dd > THRESH ) return false; - dd = fabsf( t.mNormal.y - mNormal.y ); - if ( dd > THRESH ) return false; - dd = fabsf( t.mNormal.z - mNormal.z ); - if ( dd > THRESH ) return false; - return true; - } - - bool hasIndex(unsigned int i) const - { - if ( i == mI1 || i == mI2 || i == mI3 ) return true; - return false; - } - - bool sharesEdge(const CTri &t) const - { - bool ret = false; - unsigned int count = 0; - - if ( t.hasIndex(mI1) ) count++; - if ( t.hasIndex(mI2) ) count++; - if ( t.hasIndex(mI3) ) count++; - - if ( count >= 2 ) ret = true; - - return ret; - } - - void debug(unsigned int color,ConvexDecompInterface *callback) - { - callback->ConvexDebugTri( mP1.Ptr(), mP2.Ptr(), mP3.Ptr(), color ); - callback->ConvexDebugTri( mP1.Ptr(), mP1.Ptr(), mNear1.Ptr(), 0xFF0000 ); - callback->ConvexDebugTri( mP2.Ptr(), mP2.Ptr(), mNear2.Ptr(), 0xFF0000 ); - callback->ConvexDebugTri( mP2.Ptr(), mP3.Ptr(), mNear3.Ptr(), 0xFF0000 ); - callback->ConvexDebugPoint( mNear1.Ptr(), 0.01f, 0xFF0000 ); - callback->ConvexDebugPoint( mNear2.Ptr(), 0.01f, 0xFF0000 ); - callback->ConvexDebugPoint( mNear3.Ptr(), 0.01f, 0xFF0000 ); - } - - float area(void) - { - float a = mConcavity*mP1.Area(mP2,mP3); - return a; - } - - void addWeighted(WpointVector &list,ConvexDecompInterface *callback) - { - - Wpoint p1(mP1,mC1); - Wpoint p2(mP2,mC2); - Wpoint p3(mP3,mC3); - - Vector3d d1 = mNear1 - mP1; - Vector3d d2 = mNear2 - mP2; - Vector3d d3 = mNear3 - mP3; - - d1*=WSCALE; - d2*=WSCALE; - d3*=WSCALE; - - d1 = d1 + mP1; - d2 = d2 + mP2; - d3 = d3 + mP3; - - Wpoint p4(d1,mC1); - Wpoint p5(d2,mC2); - Wpoint p6(d3,mC3); - - list.push_back(p1); - list.push_back(p2); - list.push_back(p3); - - list.push_back(p4); - list.push_back(p5); - list.push_back(p6); - -#if 0 - callback->ConvexDebugPoint(mP1.Ptr(),0.01f,0x00FF00); - callback->ConvexDebugPoint(mP2.Ptr(),0.01f,0x00FF00); - callback->ConvexDebugPoint(mP3.Ptr(),0.01f,0x00FF00); - callback->ConvexDebugPoint(d1.Ptr(),0.01f,0xFF0000); - callback->ConvexDebugPoint(d2.Ptr(),0.01f,0xFF0000); - callback->ConvexDebugPoint(d3.Ptr(),0.01f,0xFF0000); - - callback->ConvexDebugTri(mP1.Ptr(), d1.Ptr(), d1.Ptr(),0x00FF00); - callback->ConvexDebugTri(mP2.Ptr(), d2.Ptr(), d2.Ptr(),0x00FF00); - callback->ConvexDebugTri(mP3.Ptr(), d3.Ptr(), d3.Ptr(),0x00FF00); - - Vector3d np1 = mP1 + mNormal*0.05f; - Vector3d np2 = mP2 + mNormal*0.05f; - Vector3d np3 = mP3 + mNormal*0.05f; - - callback->ConvexDebugTri(mP1.Ptr(), np1.Ptr(), np1.Ptr(), 0xFF00FF ); - callback->ConvexDebugTri(mP2.Ptr(), np2.Ptr(), np2.Ptr(), 0xFF00FF ); - callback->ConvexDebugTri(mP3.Ptr(), np3.Ptr(), np3.Ptr(), 0xFF00FF ); - - callback->ConvexDebugPoint( np1.Ptr(), 0.01F, 0XFF00FF ); - callback->ConvexDebugPoint( np2.Ptr(), 0.01F, 0XFF00FF ); - callback->ConvexDebugPoint( np3.Ptr(), 0.01F, 0XFF00FF ); - -#endif - - - - } - - Vector3d mP1; - Vector3d mP2; - Vector3d mP3; - Vector3d mNear1; - Vector3d mNear2; - Vector3d mNear3; - Vector3d mNormal; - float mPlaneD; - float mConcavity; - float mC1; - float mC2; - float mC3; - unsigned int mI1; - unsigned int mI2; - unsigned int mI3; - int mProcessed; // already been added... -}; - -typedef std::vector< CTri > CTriVector; - -bool featureMatch(CTri &m,const CTriVector &tris,ConvexDecompInterface *callback,const CTriVector &input_mesh) -{ - - bool ret = false; - - float neardot = 0.707f; - - m.mConcavity = 0; - - //gLog->Display("*********** FEATURE MATCH *************\r\n"); - //gLog->Display("Plane: %0.4f,%0.4f,%0.4f %0.4f\r\n", m.mNormal.x, m.mNormal.y, m.mNormal.z, m.mPlaneD ); - //gLog->Display("*********************************************\r\n"); - - CTriVector::const_iterator i; - - CTri nearest; - - - for (i=tris.begin(); i!=tris.end(); ++i) - { - const CTri &t = (*i); - - - //gLog->Display(" HullPlane: %0.4f,%0.4f,%0.4f %0.4f\r\n", t.mNormal.x, t.mNormal.y, t.mNormal.z, t.mPlaneD ); - - if ( t.samePlane(m) ) - { - //gLog->Display("*** PLANE MATCH!!!\r\n"); - ret = false; - break; - } - - float dot = t.mNormal.Dot(m.mNormal); - - if ( dot > neardot ) - { - - float d1 = t.planeDistance( m.mP1 ); - float d2 = t.planeDistance( m.mP2 ); - float d3 = t.planeDistance( m.mP3 ); - - if ( d1 > 0.001f || d2 > 0.001f || d3 > 0.001f ) // can't be near coplaner! - { - - neardot = dot; - - Vector3d n1,n2,n3; - - t.raySect( m.mP1, m.mNormal, m.mNear1 ); - t.raySect( m.mP2, m.mNormal, m.mNear2 ); - t.raySect( m.mP3, m.mNormal, m.mNear3 ); - - nearest = t; - - ret = true; - } - - } - } - - if ( ret ) - { - if ( 0 ) - { - CTriVector::const_iterator i; - for (i=input_mesh.begin(); i!=input_mesh.end(); ++i) - { - const CTri &c = (*i); - if ( c.mI1 != m.mI1 && c.mI2 != m.mI2 && c.mI3 != m.mI3 ) - { - c.clip( m.mP1, m.mNear1 ); - c.clip( m.mP2, m.mNear2 ); - c.clip( m.mP3, m.mNear3 ); - } - } - } - - //gLog->Display("*********************************************\r\n"); - //gLog->Display(" HullPlaneNearest: %0.4f,%0.4f,%0.4f %0.4f\r\n", nearest.mNormal.x, nearest.mNormal.y, nearest.mNormal.z, nearest.mPlaneD ); - - m.mC1 = m.mP1.Distance( m.mNear1 ); - m.mC2 = m.mP2.Distance( m.mNear2 ); - m.mC3 = m.mP3.Distance( m.mNear3 ); - - m.mConcavity = m.mC1; - - if ( m.mC2 > m.mConcavity ) m.mConcavity = m.mC2; - if ( m.mC3 > m.mConcavity ) m.mConcavity = m.mC3; - - #if 0 - callback->ConvexDebugTri( m.mP1.Ptr(), m.mP2.Ptr(), m.mP3.Ptr(), 0x00FF00 ); - callback->ConvexDebugTri( m.mNear1.Ptr(), m.mNear2.Ptr(), m.mNear3.Ptr(), 0xFF0000 ); - - callback->ConvexDebugTri( m.mP1.Ptr(), m.mP1.Ptr(), m.mNear1.Ptr(), 0xFFFF00 ); - callback->ConvexDebugTri( m.mP2.Ptr(), m.mP2.Ptr(), m.mNear2.Ptr(), 0xFFFF00 ); - callback->ConvexDebugTri( m.mP3.Ptr(), m.mP3.Ptr(), m.mNear3.Ptr(), 0xFFFF00 ); - #endif - - } - else - { - //gLog->Display("No match\r\n"); - } - - //gLog->Display("*********************************************\r\n"); - return ret; -} - -bool isFeatureTri(CTri &t,CTriVector &flist,float fc,ConvexDecompInterface *callback,unsigned int color) -{ - bool ret = false; - - if ( t.mProcessed == 0 ) // if not already processed - { - - float c = t.mConcavity / fc; // must be within 80% of the concavity of the parent. - - if ( c > 0.85f ) - { - // see if this triangle is a 'feature' triangle. Meaning it shares an - // edge with any existing feature triangle and is within roughly the same - // concavity of the parent. - if ( flist.size() ) - { - CTriVector::iterator i; - for (i=flist.begin(); i!=flist.end(); ++i) - { - CTri &ftri = (*i); - if ( ftri.sharesEdge(t) ) - { - t.mProcessed = 2; // it is now part of a feature. - flist.push_back(t); // add it to the feature list. -// callback->ConvexDebugTri( t.mP1.Ptr(), t.mP2.Ptr(),t.mP3.Ptr(), color ); - ret = true; - break; - } - } - } - else - { - t.mProcessed = 2; - flist.push_back(t); // add it to the feature list. -// callback->ConvexDebugTri( t.mP1.Ptr(), t.mP2.Ptr(),t.mP3.Ptr(), color ); - ret = true; - } - } - else - { - t.mProcessed = 1; // eliminated for this feature, but might be valid for the next one.. - } - - } - return ret; -} - -float computeConcavity(unsigned int vcount, - const float *vertices, - unsigned int tcount, - const unsigned int *indices, - ConvexDecompInterface *callback, - float *plane, // plane equation to split on - float &volume) -{ - - - float cret = 0; - volume = 1; - - HullResult result; - HullLibrary hl; - HullDesc desc; - - desc.mMaxFaces = 256; - desc.mMaxVertices = 256; - desc.SetHullFlag(QF_TRIANGLES); - - - desc.mVcount = vcount; - desc.mVertices = vertices; - desc.mVertexStride = sizeof(float)*3; - - HullError ret = hl.CreateConvexHull(desc,result); - - if ( ret == QE_OK ) - { -#if 0 - float bmin[3]; - float bmax[3]; - - float dx = bmax[0] - bmin[0]; - float dy = bmax[1] - bmin[1]; - float dz = bmax[2] - bmin[2]; - - Vector3d center; - - center.x = bmin[0] + dx*0.5f; - center.y = bmin[1] + dy*0.5f; - center.z = bmin[2] + dz*0.5f; -#endif - - volume = computeMeshVolume2( result.mOutputVertices, result.mNumFaces, result.mIndices ); - -#if 1 - // ok..now..for each triangle on the original mesh.. - // we extrude the points to the nearest point on the hull. - const unsigned int *source = result.mIndices; - - CTriVector tris; - - for (unsigned int i=0; iConvexDebugTri(p1,p2,p3,0xFFFFFF); - - CTri t(p1,p2,p3,i1,i2,i3); // - tris.push_back(t); - } - - // we have not pre-computed the plane equation for each triangle in the convex hull.. - - float totalVolume = 0; - - CTriVector ftris; // 'feature' triangles. - - const unsigned int *src = indices; - - - float maxc=0; - - - if ( 1 ) - { - CTriVector input_mesh; - if ( 1 ) - { - const unsigned int *src = indices; - for (unsigned int i=0; i CONCAVE_THRESH ) - { - - if ( t.mConcavity > maxc ) - { - maxc = t.mConcavity; - maxctri = t; - } - - float v = t.getVolume(0); - totalVolume+=v; - ftris.push_back(t); - } - - } - } - -#if 0 - if ( ftris.size() && 0 ) - { - - // ok..now we extract the triangles which form the maximum concavity. - CTriVector major_feature; - float maxarea = 0; - - while ( maxc > CONCAVE_THRESH ) - { - - unsigned int color = getDebugColor(); // - - CTriVector flist; - - bool found; - - float totalarea = 0; - - do - { - found = false; - CTriVector::iterator i; - for (i=ftris.begin(); i!=ftris.end(); ++i) - { - CTri &t = (*i); - if ( isFeatureTri(t,flist,maxc,callback,color) ) - { - found = true; - totalarea+=t.area(); - } - } - } while ( found ); - - - if ( totalarea > maxarea ) - { - major_feature = flist; - maxarea = totalarea; - } - - maxc = 0; - - for (unsigned int i=0; i maxc ) - { - maxc = t.mConcavity; - } - } - } - - } - - unsigned int color = getDebugColor(); - - WpointVector list; - for (unsigned int i=0; i -#include -#include -#include -#include - -#include "fitsphere.h" - - -/*---------------------------------------------------------------------- - Copyright (c) 2004 Open Dynamics Framework Group - www.physicstools.org - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are permitted provided - that the following conditions are met: - - Redistributions of source code must retain the above copyright notice, this list of conditions - and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - Neither the name of the Open Dynamics Framework Group nor the names of its contributors may - be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER - IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -// http://codesuppository.blogspot.com -// -// mailto: jratcliff@infiniplex.net -// -// http://www.amillionpixels.us -// -/* -An Efficient Bounding Sphere -by Jack Ritter -from "Graphics Gems", Academic Press, 1990 -*/ - -/* Routine to calculate tight bounding sphere over */ -/* a set of points in 3D */ -/* This contains the routine find_bounding_sphere(), */ -/* the struct definition, and the globals used for parameters. */ -/* The abs() of all coordinates must be < BIGNUMBER */ -/* Code written by Jack Ritter and Lyle Rains. */ - -#define BIGNUMBER 100000000.0 /* hundred million */ - -static inline void Set(float *n,float x,float y,float z) -{ - n[0] = x; - n[1] = y; - n[2] = z; -} - -static inline void Copy(float *dest,const float *source) -{ - dest[0] = source[0]; - dest[1] = source[1]; - dest[2] = source[2]; -} - -float computeBoundingSphere(unsigned int vcount,const float *points,float *center) -{ - - float mRadius; - float mRadius2; - - float xmin[3]; - float xmax[3]; - float ymin[3]; - float ymax[3]; - float zmin[3]; - float zmax[3]; - float dia1[3]; - float dia2[3]; - - /* FIRST PASS: find 6 minima/maxima points */ - Set(xmin,BIGNUMBER,BIGNUMBER,BIGNUMBER); - Set(xmax,-BIGNUMBER,-BIGNUMBER,-BIGNUMBER); - Set(ymin,BIGNUMBER,BIGNUMBER,BIGNUMBER); - Set(ymax,-BIGNUMBER,-BIGNUMBER,-BIGNUMBER); - Set(zmin,BIGNUMBER,BIGNUMBER,BIGNUMBER); - Set(zmax,-BIGNUMBER,-BIGNUMBER,-BIGNUMBER); - - for (unsigned i=0; ixmax[0]) - Copy(xmax,caller_p); - if (caller_p[1]ymax[1]) - Copy(ymax,caller_p); - if (caller_p[2]zmax[2]) - Copy(zmax,caller_p); - } - - /* Set xspan = distance between the 2 points xmin & xmax (squared) */ - float dx = xmax[0] - xmin[0]; - float dy = xmax[1] - xmin[1]; - float dz = xmax[2] - xmin[2]; - float xspan = dx*dx + dy*dy + dz*dz; - - /* Same for y & z spans */ - dx = ymax[0] - ymin[0]; - dy = ymax[1] - ymin[1]; - dz = ymax[2] - ymin[2]; - float yspan = dx*dx + dy*dy + dz*dz; - - dx = zmax[0] - zmin[0]; - dy = zmax[1] - zmin[1]; - dz = zmax[2] - zmin[2]; - float zspan = dx*dx + dy*dy + dz*dz; - - /* Set points dia1 & dia2 to the maximally separated pair */ - Copy(dia1,xmin); - Copy(dia2,xmax); /* assume xspan biggest */ - float maxspan = xspan; - - if (yspan>maxspan) - { - maxspan = yspan; - Copy(dia1,ymin); - Copy(dia2,ymax); - } - - if (zspan>maxspan) - { - Copy(dia1,zmin); - Copy(dia2,zmax); - } - - - /* dia1,dia2 is a diameter of initial sphere */ - /* calc initial center */ - center[0] = (dia1[0]+dia2[0])*0.5f; - center[1] = (dia1[1]+dia2[1])*0.5f; - center[2] = (dia1[2]+dia2[2])*0.5f; - - /* calculate initial radius**2 and radius */ - - dx = dia2[0]-center[0]; /* x component of radius vector */ - dy = dia2[1]-center[1]; /* y component of radius vector */ - dz = dia2[2]-center[2]; /* z component of radius vector */ - - mRadius2 = dx*dx + dy*dy + dz*dz; - mRadius = float(sqrt(mRadius2)); - - /* SECOND PASS: increment current sphere */ - - if ( 1 ) - { - for (unsigned i=0; i mRadius2) /* do r**2 test first */ - { /* this point is outside of current sphere */ - float old_to_p = float(sqrt(old_to_p_sq)); - /* calc radius of new sphere */ - mRadius = (mRadius + old_to_p) * 0.5f; - mRadius2 = mRadius*mRadius; /* for next r**2 compare */ - float old_to_new = old_to_p - mRadius; - - /* calc center of new sphere */ - - float recip = 1.0f /old_to_p; - - float cx = (mRadius*center[0] + old_to_new*caller_p[0]) * recip; - float cy = (mRadius*center[1] + old_to_new*caller_p[1]) * recip; - float cz = (mRadius*center[2] + old_to_new*caller_p[2]) * recip; - - Set(center,cx,cy,cz); - } - } - } - - return mRadius; -} - - diff --git a/extern/bullet/src/Extras/ConvexDecomposition/fitsphere.h b/extern/bullet/src/Extras/ConvexDecomposition/fitsphere.h deleted file mode 100644 index cd4a565c5e13..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/fitsphere.h +++ /dev/null @@ -1,43 +0,0 @@ -#ifndef FIT_SPHERE_H - -#define FIT_SPHERE_H - -/*---------------------------------------------------------------------- - Copyright (c) 2004 Open Dynamics Framework Group - www.physicstools.org - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are permitted provided - that the following conditions are met: - - Redistributions of source code must retain the above copyright notice, this list of conditions - and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - Neither the name of the Open Dynamics Framework Group nor the names of its contributors may - be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER - IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -// http://codesuppository.blogspot.com -// -// mailto: jratcliff@infiniplex.net -// -// http://www.amillionpixels.us -// - - - -float computeBoundingSphere(unsigned int vcount,const float *points,float *center); - -#endif diff --git a/extern/bullet/src/Extras/ConvexDecomposition/float_math.cpp b/extern/bullet/src/Extras/ConvexDecomposition/float_math.cpp deleted file mode 100644 index 38c699b59a54..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/float_math.cpp +++ /dev/null @@ -1,257 +0,0 @@ -#include "float_math.h" - -#include -#include -#include -#include -#include - - -/*---------------------------------------------------------------------- - Copyright (c) 2004 Open Dynamics Framework Group - www.physicstools.org - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are permitted provided - that the following conditions are met: - - Redistributions of source code must retain the above copyright notice, this list of conditions - and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - Neither the name of the Open Dynamics Framework Group nor the names of its contributors may - be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER - IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -// http://codesuppository.blogspot.com -// -// mailto: jratcliff@infiniplex.net -// -// http://www.amillionpixels.us -// - -void fm_inverseRT(const float *matrix,const float *pos,float *t) // inverse rotate translate the point. -{ - - float _x = pos[0] - matrix[3*4+0]; - float _y = pos[1] - matrix[3*4+1]; - float _z = pos[2] - matrix[3*4+2]; - - // Multiply inverse-translated source vector by inverted rotation transform - - t[0] = (matrix[0*4+0] * _x) + (matrix[0*4+1] * _y) + (matrix[0*4+2] * _z); - t[1] = (matrix[1*4+0] * _x) + (matrix[1*4+1] * _y) + (matrix[1*4+2] * _z); - t[2] = (matrix[2*4+0] * _x) + (matrix[2*4+1] * _y) + (matrix[2*4+2] * _z); - -} - - -void fm_identity(float *matrix) // set 4x4 matrix to identity. -{ - matrix[0*4+0] = 1; - matrix[1*4+1] = 1; - matrix[2*4+2] = 1; - matrix[3*4+3] = 1; - - matrix[1*4+0] = 0; - matrix[2*4+0] = 0; - matrix[3*4+0] = 0; - - matrix[0*4+1] = 0; - matrix[2*4+1] = 0; - matrix[3*4+1] = 0; - - matrix[0*4+2] = 0; - matrix[1*4+2] = 0; - matrix[3*4+2] = 0; - - matrix[0*4+3] = 0; - matrix[1*4+3] = 0; - matrix[2*4+3] = 0; - -} - -void fm_eulerMatrix(float ax,float ay,float az,float *matrix) // convert euler (in radians) to a dest 4x4 matrix (translation set to zero) -{ - float quat[4]; - fm_eulerToQuat(ax,ay,az,quat); - fm_quatToMatrix(quat,matrix); -} - -void fm_getAABB(unsigned int vcount,const float *points,unsigned int pstride,float *bmin,float *bmax) -{ - - const unsigned char *source = (const unsigned char *) points; - - bmin[0] = points[0]; - bmin[1] = points[1]; - bmin[2] = points[2]; - - bmax[0] = points[0]; - bmax[1] = points[1]; - bmax[2] = points[2]; - - - for (unsigned int i=1; i bmax[0] ) bmax[0] = p[0]; - if ( p[1] > bmax[1] ) bmax[1] = p[1]; - if ( p[2] > bmax[2] ) bmax[2] = p[2]; - - } -} - - -void fm_eulerToQuat(float roll,float pitch,float yaw,float *quat) // convert euler angles to quaternion. -{ - roll *= 0.5f; - pitch *= 0.5f; - yaw *= 0.5f; - - float cr = cosf(roll); - float cp = cosf(pitch); - float cy = cosf(yaw); - - float sr = sinf(roll); - float sp = sinf(pitch); - float sy = sinf(yaw); - - float cpcy = cp * cy; - float spsy = sp * sy; - float spcy = sp * cy; - float cpsy = cp * sy; - - quat[0] = ( sr * cpcy - cr * spsy); - quat[1] = ( cr * spcy + sr * cpsy); - quat[2] = ( cr * cpsy - sr * spcy); - quat[3] = cr * cpcy + sr * spsy; -} - -void fm_quatToMatrix(const float *quat,float *matrix) // convert quaterinion rotation to matrix, zeros out the translation component. -{ - - float xx = quat[0]*quat[0]; - float yy = quat[1]*quat[1]; - float zz = quat[2]*quat[2]; - float xy = quat[0]*quat[1]; - float xz = quat[0]*quat[2]; - float yz = quat[1]*quat[2]; - float wx = quat[3]*quat[0]; - float wy = quat[3]*quat[1]; - float wz = quat[3]*quat[2]; - - matrix[0*4+0] = 1 - 2 * ( yy + zz ); - matrix[1*4+0] = 2 * ( xy - wz ); - matrix[2*4+0] = 2 * ( xz + wy ); - - matrix[0*4+1] = 2 * ( xy + wz ); - matrix[1*4+1] = 1 - 2 * ( xx + zz ); - matrix[2*4+1] = 2 * ( yz - wx ); - - matrix[0*4+2] = 2 * ( xz - wy ); - matrix[1*4+2] = 2 * ( yz + wx ); - matrix[2*4+2] = 1 - 2 * ( xx + yy ); - - matrix[3*4+0] = matrix[3*4+1] = matrix[3*4+2] = 0.0f; - matrix[0*4+3] = matrix[1*4+3] = matrix[2*4+3] = 0.0f; - matrix[3*4+3] = 1.0f; - -} - - -void fm_quatRotate(const float *quat,const float *v,float *r) // rotate a vector directly by a quaternion. -{ - float left[4]; - - left[0] = quat[3]*v[0] + quat[1]*v[2] - v[1]*quat[2]; - left[1] = quat[3]*v[1] + quat[2]*v[0] - v[2]*quat[0]; - left[2] = quat[3]*v[2] + quat[0]*v[1] - v[0]*quat[1]; - left[3] = - quat[0]*v[0] - quat[1]*v[1] - quat[2]*v[2]; - - r[0] = (left[3]*-quat[0]) + (quat[3]*left[0]) + (left[1]*-quat[2]) - (-quat[1]*left[2]); - r[1] = (left[3]*-quat[1]) + (quat[3]*left[1]) + (left[2]*-quat[0]) - (-quat[2]*left[0]); - r[2] = (left[3]*-quat[2]) + (quat[3]*left[2]) + (left[0]*-quat[1]) - (-quat[0]*left[1]); - -} - - -void fm_getTranslation(const float *matrix,float *t) -{ - t[0] = matrix[3*4+0]; - t[1] = matrix[3*4+1]; - t[2] = matrix[3*4+2]; -} - -void fm_matrixToQuat(const float *matrix,float *quat) // convert the 3x3 portion of a 4x4 matrix into a quaterion as x,y,z,w -{ - - float tr = matrix[0*4+0] + matrix[1*4+1] + matrix[2*4+2]; - - // check the diagonal - - if (tr > 0.0f ) - { - float s = (float) sqrt ( (double) (tr + 1.0f) ); - quat[3] = s * 0.5f; - s = 0.5f / s; - quat[0] = (matrix[1*4+2] - matrix[2*4+1]) * s; - quat[1] = (matrix[2*4+0] - matrix[0*4+2]) * s; - quat[2] = (matrix[0*4+1] - matrix[1*4+0]) * s; - - } - else - { - // diagonal is negative - int nxt[3] = {1, 2, 0}; - float qa[4]; - - int i = 0; - - if (matrix[1*4+1] > matrix[0*4+0]) i = 1; - if (matrix[2*4+2] > matrix[i*4+i]) i = 2; - - int j = nxt[i]; - int k = nxt[j]; - - float s = sqrtf ( ((matrix[i*4+i] - (matrix[j*4+j] + matrix[k*4+k])) + 1.0f) ); - - qa[i] = s * 0.5f; - - if (s != 0.0f ) s = 0.5f / s; - - qa[3] = (matrix[j*4+k] - matrix[k*4+j]) * s; - qa[j] = (matrix[i*4+j] + matrix[j*4+i]) * s; - qa[k] = (matrix[i*4+k] + matrix[k*4+i]) * s; - - quat[0] = qa[0]; - quat[1] = qa[1]; - quat[2] = qa[2]; - quat[3] = qa[3]; - } - - -} - - -float fm_sphereVolume(float radius) // return's the volume of a sphere of this radius (4/3 PI * R cubed ) -{ - return (4.0f / 3.0f ) * FM_PI * radius * radius * radius; -} diff --git a/extern/bullet/src/Extras/ConvexDecomposition/float_math.h b/extern/bullet/src/Extras/ConvexDecomposition/float_math.h deleted file mode 100644 index d6046d3b05a8..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/float_math.h +++ /dev/null @@ -1,72 +0,0 @@ -#ifndef FLOAT_MATH_H - -#define FLOAT_MATH_H - -#ifdef _WIN32 - #pragma warning(disable : 4324) // disable padding warning - #pragma warning(disable : 4244) // disable padding warning - #pragma warning(disable : 4267) // possible loss of data - #pragma warning(disable:4530) // Disable the exception disable but used in MSCV Stl warning. - #pragma warning(disable:4996) //Turn off warnings about deprecated C routines - #pragma warning(disable:4786) // Disable the "debug name too long" warning -#endif - -/*---------------------------------------------------------------------- - Copyright (c) 2004 Open Dynamics Framework Group - www.physicstools.org - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are permitted provided - that the following conditions are met: - - Redistributions of source code must retain the above copyright notice, this list of conditions - and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - Neither the name of the Open Dynamics Framework Group nor the names of its contributors may - be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER - IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -// http://codesuppository.blogspot.com -// -// mailto: jratcliff@infiniplex.net -// -// http://www.amillionpixels.us -// - - -// a set of routines that last you do common 3d math -// operations without any vector, matrix, or quaternion -// classes or templates. -// -// a vector (or point) is a 'float *' to 3 floating point numbers. -// a matrix is a 'float *' to an array of 16 floating point numbers representing a 4x4 transformation matrix compatible with D3D or OGL -// a quaternion is a 'float *' to 4 floats representing a quaternion x,y,z,w - -const float FM_PI = 3.141592654f; -const float FM_DEG_TO_RAD = ((2.0f * FM_PI) / 360.0f); -const float FM_RAD_TO_DEG = (360.0f / (2.0f * FM_PI)); - -void fm_identity(float *matrix); // set 4x4 matrix to identity. -void fm_inverseRT(const float *matrix,const float *pos,float *t); // inverse rotate translate the point. -void fm_eulerMatrix(float ax,float ay,float az,float *matrix); // convert euler (in radians) to a dest 4x4 matrix (translation set to zero) -void fm_getAABB(unsigned int vcount,const float *points,unsigned int pstride,float *bmin,float *bmax); -void fm_eulerToQuat(float roll,float pitch,float yaw,float *quat); // convert euler angles to quaternion. -void fm_quatToMatrix(const float *quat,float *matrix); // convert quaterinion rotation to matrix, translation set to zero. -void fm_quatRotate(const float *quat,const float *v,float *r); // rotate a vector directly by a quaternion. -void fm_getTranslation(const float *matrix,float *t); -void fm_matrixToQuat(const float *matrix,float *quat); // convert the 3x3 portion of a 4x4 matrix into a quaterion as x,y,z,w -float fm_sphereVolume(float radius); // return's the volume of a sphere of this radius (4/3 PI * R cubed ) - -#endif diff --git a/extern/bullet/src/Extras/ConvexDecomposition/meshvolume.cpp b/extern/bullet/src/Extras/ConvexDecomposition/meshvolume.cpp deleted file mode 100644 index b9dfa174d30a..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/meshvolume.cpp +++ /dev/null @@ -1,128 +0,0 @@ -#include "float_math.h" -#include "meshvolume.h" - -/*---------------------------------------------------------------------- - Copyright (c) 2004 Open Dynamics Framework Group - www.physicstools.org - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are permitted provided - that the following conditions are met: - - Redistributions of source code must retain the above copyright notice, this list of conditions - and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - Neither the name of the Open Dynamics Framework Group nor the names of its contributors may - be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER - IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -// http://codesuppository.blogspot.com -// -// mailto: jratcliff@infiniplex.net -// -// http://www.amillionpixels.us -// - -inline float det(const float *p1,const float *p2,const float *p3) -{ - return p1[0]*p2[1]*p3[2] + p2[0]*p3[1]*p1[2] + p3[0]*p1[1]*p2[2] -p1[0]*p3[1]*p2[2] - p2[0]*p1[1]*p3[2] - p3[0]*p2[1]*p1[2]; -} - -float computeMeshVolume(const float *vertices,unsigned int tcount,const unsigned int *indices) -{ - float volume = 0; - - for (unsigned int i=0; i -#include -#include -#include - -#include "planetri.h" - -/*---------------------------------------------------------------------- - Copyright (c) 2004 Open Dynamics Framework Group - www.physicstools.org - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are permitted provided - that the following conditions are met: - - Redistributions of source code must retain the above copyright notice, this list of conditions - and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - Neither the name of the Open Dynamics Framework Group nor the names of its contributors may - be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER - IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -// http://codesuppository.blogspot.com -// -// mailto: jratcliff@infiniplex.net -// -// http://www.amillionpixels.us -// - -static inline float DistToPt(const float *p,const float *plane) -{ - float x = p[0]; - float y = p[1]; - float z = p[2]; - float d = x*plane[0] + y*plane[1] + z*plane[2] + plane[3]; - return d; -} - - -static PlaneTriResult getSidePlane(const float *p,const float *plane,float epsilon) -{ - - float d = DistToPt(p,plane); - - if ( (d+epsilon) > 0 ) - return PTR_FRONT; // it is 'in front' within the provided epsilon value. - - return PTR_BACK; -} - -static void add(const float *p,float *dest,unsigned int tstride,unsigned int &pcount) -{ - char *d = (char *) dest; - d = d + pcount*tstride; - dest = (float *) d; - dest[0] = p[0]; - dest[1] = p[1]; - dest[2] = p[2]; - pcount++; - assert( pcount <= 4 ); -} - - -// assumes that the points are on opposite sides of the plane! -static void intersect(const float *p1,const float *p2,float *split,const float *plane) -{ - - float dp1 = DistToPt(p1,plane); - - float dir[3]; - - dir[0] = p2[0] - p1[0]; - dir[1] = p2[1] - p1[1]; - dir[2] = p2[2] - p1[2]; - - float dot1 = dir[0]*plane[0] + dir[1]*plane[1] + dir[2]*plane[2]; - float dot2 = dp1 - plane[3]; - - float t = -(plane[3] + dot2 ) / dot1; - - split[0] = (dir[0]*t)+p1[0]; - split[1] = (dir[1]*t)+p1[1]; - split[2] = (dir[2]*t)+p1[2]; - -} - -PlaneTriResult planeTriIntersection(const float *plane, // the plane equation in Ax+By+Cz+D format - const float *triangle, // the source triangle. - unsigned int tstride, // stride in bytes of the input and output triangles - float epsilon, // the co-planer epsilon value. - float *front, // the triangle in front of the - unsigned int &fcount, // number of vertices in the 'front' triangle - float *back, // the triangle in back of the plane - unsigned int &bcount) // the number of vertices in the 'back' triangle. -{ - fcount = 0; - bcount = 0; - - const char *tsource = (const char *) triangle; - - // get the three vertices of the triangle. - const float *p1 = (const float *) (tsource); - const float *p2 = (const float *) (tsource+tstride); - const float *p3 = (const float *) (tsource+tstride*2); - - - PlaneTriResult r1 = getSidePlane(p1,plane,epsilon); // compute the side of the plane each vertex is on - PlaneTriResult r2 = getSidePlane(p2,plane,epsilon); - PlaneTriResult r3 = getSidePlane(p3,plane,epsilon); - - if ( r1 == r2 && r1 == r3 ) // if all three vertices are on the same side of the plane. - { - if ( r1 == PTR_FRONT ) // if all three are in front of the plane, then copy to the 'front' output triangle. - { - add(p1,front,tstride,fcount); - add(p2,front,tstride,fcount); - add(p3,front,tstride,fcount); - } - else - { - add(p1,back,tstride,bcount); // if all three are in 'abck' then copy to the 'back' output triangle. - add(p2,back,tstride,bcount); - add(p3,back,tstride,bcount); - } - return r1; // if all three points are on the same side of the plane return result - } - - // ok.. we need to split the triangle at the plane. - - // First test ray segment P1 to P2 - if ( r1 == r2 ) // if these are both on the same side... - { - if ( r1 == PTR_FRONT ) - { - add( p1, front, tstride, fcount ); - add( p2, front, tstride, fcount ); - } - else - { - add( p1, back, tstride, bcount ); - add( p2, back, tstride, bcount ); - } - } - else - { - float split[3]; // split the point - intersect(p1,p2,split,plane); - - if ( r1 == PTR_FRONT ) - { - - add(p1, front, tstride, fcount ); - add(split, front, tstride, fcount ); - - add(split, back, tstride, bcount ); - add(p2, back, tstride, bcount ); - - } - else - { - add(p1, back, tstride, bcount ); - add(split, back, tstride, bcount ); - - add(split, front, tstride, fcount ); - add(p2, front, tstride, fcount ); - } - - } - - // Next test ray segment P2 to P3 - if ( r2 == r3 ) // if these are both on the same side... - { - if ( r3 == PTR_FRONT ) - { - add( p3, front, tstride, fcount ); - } - else - { - add( p3, back, tstride, bcount ); - } - } - else - { - float split[3]; // split the point - intersect(p2,p3,split,plane); - - if ( r3 == PTR_FRONT ) - { - add(split, front, tstride, fcount ); - add(split, back, tstride, bcount ); - - add(p3, front, tstride, fcount ); - } - else - { - add(split, front, tstride, fcount ); - add(split, back, tstride, bcount ); - - add(p3, back, tstride, bcount ); - } - } - - // Next test ray segment P3 to P1 - if ( r3 != r1 ) // if these are both on the same side... - { - float split[3]; // split the point - - intersect(p3,p1,split,plane); - - if ( r1 == PTR_FRONT ) - { - add(split, front, tstride, fcount ); - add(split, back, tstride, bcount ); - } - else - { - add(split, front, tstride, fcount ); - add(split, back, tstride, bcount ); - } - } - - - - return PTR_SPLIT; -} diff --git a/extern/bullet/src/Extras/ConvexDecomposition/planetri.h b/extern/bullet/src/Extras/ConvexDecomposition/planetri.h deleted file mode 100644 index 780ac854aac0..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/planetri.h +++ /dev/null @@ -1,58 +0,0 @@ -#ifndef PLANE_TRI_H - -#define PLANE_TRI_H - -/*---------------------------------------------------------------------- - Copyright (c) 2004 Open Dynamics Framework Group - www.physicstools.org - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are permitted provided - that the following conditions are met: - - Redistributions of source code must retain the above copyright notice, this list of conditions - and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - Neither the name of the Open Dynamics Framework Group nor the names of its contributors may - be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER - IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -// http://codesuppository.blogspot.com -// -// mailto: jratcliff@infiniplex.net -// -// http://www.amillionpixels.us -// - - - -enum PlaneTriResult -{ - PTR_FRONT, - PTR_BACK, - PTR_SPLIT -}; - -PlaneTriResult planeTriIntersection(const float *plane, // the plane equation in Ax+By+Cz+D format - const float *triangle, // the source position triangle. - unsigned int tstride, // stride in bytes between vertices of the triangle. - float epsilon, // the co-planer epsilon value. - float *front, // the triangle in front of the - unsigned int &fcount, // number of vertices in the 'front' triangle. - float *back, // the triangle in back of the plane - unsigned int &bcount); // the number of vertices in the 'back' triangle. - - -#endif diff --git a/extern/bullet/src/Extras/ConvexDecomposition/premake4.lua b/extern/bullet/src/Extras/ConvexDecomposition/premake4.lua deleted file mode 100644 index 9310593a71b2..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/premake4.lua +++ /dev/null @@ -1,12 +0,0 @@ - project "ConvexDecomposition" - - kind "StaticLib" - - includedirs {".","../../src"} - if os.is("Linux") then - buildoptions{"-fPIC"} - end - files { - "**.cpp", - "**.h" - } \ No newline at end of file diff --git a/extern/bullet/src/Extras/ConvexDecomposition/raytri.cpp b/extern/bullet/src/Extras/ConvexDecomposition/raytri.cpp deleted file mode 100644 index 83b076a20d28..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/raytri.cpp +++ /dev/null @@ -1,134 +0,0 @@ -#include "float_math.h" -#include -#include -#include -#include -#include - -#include "raytri.h" - -/*---------------------------------------------------------------------- - Copyright (c) 2004 Open Dynamics Framework Group - www.physicstools.org - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are permitted provided - that the following conditions are met: - - Redistributions of source code must retain the above copyright notice, this list of conditions - and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - Neither the name of the Open Dynamics Framework Group nor the names of its contributors may - be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER - IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -// http://codesuppository.blogspot.com -// -// mailto: jratcliff@infiniplex.net -// -// http://www.amillionpixels.us -// - - -/* a = b - c */ -#define vector(a,b,c) \ - (a)[0] = (b)[0] - (c)[0]; \ - (a)[1] = (b)[1] - (c)[1]; \ - (a)[2] = (b)[2] - (c)[2]; - - - -#define innerProduct(v,q) \ - ((v)[0] * (q)[0] + \ - (v)[1] * (q)[1] + \ - (v)[2] * (q)[2]) - -#define crossProduct(a,b,c) \ - (a)[0] = (b)[1] * (c)[2] - (c)[1] * (b)[2]; \ - (a)[1] = (b)[2] * (c)[0] - (c)[2] * (b)[0]; \ - (a)[2] = (b)[0] * (c)[1] - (c)[0] * (b)[1]; - -bool rayIntersectsTriangle(const float *p,const float *d,const float *v0,const float *v1,const float *v2,float &t) -{ - - float e1[3],e2[3],h[3],s[3],q[3]; - float a,f,u,v; - - vector(e1,v1,v0); - vector(e2,v2,v0); - crossProduct(h,d,e2); - a = innerProduct(e1,h); - - if (a > -0.00001 && a < 0.00001) - return(false); - - f = 1/a; - vector(s,p,v0); - u = f * (innerProduct(s,h)); - - if (u < 0.0 || u > 1.0) - return(false); - - crossProduct(q,s,e1); - v = f * innerProduct(d,q); - if (v < 0.0 || u + v > 1.0) - return(false); - // at this stage we can compute t to find out where - // the intersection point is on the line - t = f * innerProduct(e2,q); - if (t > 0) // ray intersection - return(true); - else // this means that there is a line intersection - // but not a ray intersection - return (false); -} - - -bool lineIntersectsTriangle(const float *rayStart,const float *rayEnd,const float *p1,const float *p2,const float *p3,float *sect) -{ - float dir[3]; - - dir[0] = rayEnd[0] - rayStart[0]; - dir[1] = rayEnd[1] - rayStart[1]; - dir[2] = rayEnd[2] - rayStart[2]; - - float d = sqrtf(dir[0]*dir[0] + dir[1]*dir[1] + dir[2]*dir[2]); - float r = 1.0f / d; - - dir[0]*=r; - dir[1]*=r; - dir[2]*=r; - - - float t; - - bool ret = rayIntersectsTriangle(rayStart, dir, p1, p2, p3, t ); - - if ( ret ) - { - if ( t > d ) - { - sect[0] = rayStart[0] + dir[0]*t; - sect[1] = rayStart[1] + dir[1]*t; - sect[2] = rayStart[2] + dir[2]*t; - } - else - { - ret = false; - } - } - - return ret; -} diff --git a/extern/bullet/src/Extras/ConvexDecomposition/raytri.h b/extern/bullet/src/Extras/ConvexDecomposition/raytri.h deleted file mode 100644 index 76370c6d75da..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/raytri.h +++ /dev/null @@ -1,45 +0,0 @@ -#ifndef RAY_TRI_H - -#define RAY_TRI_H - -/*---------------------------------------------------------------------- - Copyright (c) 2004 Open Dynamics Framework Group - www.physicstools.org - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are permitted provided - that the following conditions are met: - - Redistributions of source code must retain the above copyright notice, this list of conditions - and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - Neither the name of the Open Dynamics Framework Group nor the names of its contributors may - be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER - IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -// http://codesuppository.blogspot.com -// -// mailto: jratcliff@infiniplex.net -// -// http://www.amillionpixels.us -// - - - -// returns true if the ray intersects the triangle. -bool lineIntersectsTriangle(const float *rayStart,const float *rayEnd,const float *p1,const float *p2,const float *p3,float *sect); -bool rayIntersectsTriangle(const float *p,const float *d,const float *v0,const float *v1,const float *v2,float &t); - -#endif diff --git a/extern/bullet/src/Extras/ConvexDecomposition/splitplane.cpp b/extern/bullet/src/Extras/ConvexDecomposition/splitplane.cpp deleted file mode 100644 index 2ae408e601e4..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/splitplane.cpp +++ /dev/null @@ -1,306 +0,0 @@ -#include "float_math.h" -#include -#include -#include -#include -#include -#include - - -/*---------------------------------------------------------------------- - Copyright (c) 2004 Open Dynamics Framework Group - www.physicstools.org - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are permitted provided - that the following conditions are met: - - Redistributions of source code must retain the above copyright notice, this list of conditions - and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - Neither the name of the Open Dynamics Framework Group nor the names of its contributors may - be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER - IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -// http://codesuppository.blogspot.com -// -// mailto: jratcliff@infiniplex.net -// -// http://www.amillionpixels.us -// - -#include "splitplane.h" -#include "ConvexDecomposition.h" -#include "cd_vector.h" -#include "cd_hull.h" -#include "cd_wavefront.h" -#include "bestfit.h" -#include "planetri.h" -#include "vlookup.h" -#include "meshvolume.h" - -namespace ConvexDecomposition -{ - -static void computePlane(const float *A,const float *B,const float *C,float *plane) -{ - - float vx = (B[0] - C[0]); - float vy = (B[1] - C[1]); - float vz = (B[2] - C[2]); - - float wx = (A[0] - B[0]); - float wy = (A[1] - B[1]); - float wz = (A[2] - B[2]); - - float vw_x = vy * wz - vz * wy; - float vw_y = vz * wx - vx * wz; - float vw_z = vx * wy - vy * wx; - - float mag = sqrtf((vw_x * vw_x) + (vw_y * vw_y) + (vw_z * vw_z)); - - if ( mag < 0.000001f ) - { - mag = 0; - } - else - { - mag = 1.0f/mag; - } - - float x = vw_x * mag; - float y = vw_y * mag; - float z = vw_z * mag; - - - float D = 0.0f - ((x*A[0])+(y*A[1])+(z*A[2])); - - plane[0] = x; - plane[1] = y; - plane[2] = z; - plane[3] = D; - -} - -class Rect3d -{ -public: - Rect3d(void) { }; - - Rect3d(const float *bmin,const float *bmax) - { - - mMin[0] = bmin[0]; - mMin[1] = bmin[1]; - mMin[2] = bmin[2]; - - mMax[0] = bmax[0]; - mMax[1] = bmax[1]; - mMax[2] = bmax[2]; - - } - - void SetMin(const float *bmin) - { - mMin[0] = bmin[0]; - mMin[1] = bmin[1]; - mMin[2] = bmin[2]; - } - - void SetMax(const float *bmax) - { - mMax[0] = bmax[0]; - mMax[1] = bmax[1]; - mMax[2] = bmax[2]; - } - - void SetMin(float x,float y,float z) - { - mMin[0] = x; - mMin[1] = y; - mMin[2] = z; - } - - void SetMax(float x,float y,float z) - { - mMax[0] = x; - mMax[1] = y; - mMax[2] = z; - } - - float mMin[3]; - float mMax[3]; -}; - -void splitRect(unsigned int axis, - const Rect3d &source, - Rect3d &b1, - Rect3d &b2, - const float *midpoint) -{ - switch ( axis ) - { - case 0: - b1.SetMin(source.mMin); - b1.SetMax( midpoint[0], source.mMax[1], source.mMax[2] ); - - b2.SetMin( midpoint[0], source.mMin[1], source.mMin[2] ); - b2.SetMax(source.mMax); - - break; - case 1: - b1.SetMin(source.mMin); - b1.SetMax( source.mMax[0], midpoint[1], source.mMax[2] ); - - b2.SetMin( source.mMin[0], midpoint[1], source.mMin[2] ); - b2.SetMax(source.mMax); - - break; - case 2: - b1.SetMin(source.mMin); - b1.SetMax( source.mMax[0], source.mMax[1], midpoint[2] ); - - b2.SetMin( source.mMin[0], source.mMin[1], midpoint[2] ); - b2.SetMax(source.mMax); - - break; - } -} - -bool computeSplitPlane(unsigned int vcount, - const float *vertices, - unsigned int tcount, - const unsigned int *indices, - ConvexDecompInterface *callback, - float *plane) -{ - float bmin[3] = { 1e9, 1e9, 1e9 }; - float bmax[3] = { -1e9, -1e9, -1e9 }; - - for (unsigned int i=0; i bmax[0] ) bmax[0] = p[0]; - if ( p[1] > bmax[1] ) bmax[1] = p[1]; - if ( p[2] > bmax[2] ) bmax[2] = p[2]; - - } - - float dx = bmax[0] - bmin[0]; - float dy = bmax[1] - bmin[1]; - float dz = bmax[2] - bmin[2]; - - - float laxis = dx; - - unsigned int axis = 0; - - if ( dy > dx ) - { - axis = 1; - laxis = dy; - } - - if ( dz > dx && dz > dy ) - { - axis = 2; - laxis = dz; - } - - float p1[3]; - float p2[3]; - float p3[3]; - - p3[0] = p2[0] = p1[0] = bmin[0] + dx*0.5f; - p3[1] = p2[1] = p1[1] = bmin[1] + dy*0.5f; - p3[2] = p2[2] = p1[2] = bmin[2] + dz*0.5f; - - Rect3d b(bmin,bmax); - - Rect3d b1,b2; - - splitRect(axis,b,b1,b2,p1); - - -// callback->ConvexDebugBound(b1.mMin,b1.mMax,0x00FF00); -// callback->ConvexDebugBound(b2.mMin,b2.mMax,0xFFFF00); - - switch ( axis ) - { - case 0: - p2[1] = bmin[1]; - p2[2] = bmin[2]; - - if ( dz > dy ) - { - p3[1] = bmax[1]; - p3[2] = bmin[2]; - } - else - { - p3[1] = bmin[1]; - p3[2] = bmax[2]; - } - - break; - case 1: - p2[0] = bmin[0]; - p2[2] = bmin[2]; - - if ( dx > dz ) - { - p3[0] = bmax[0]; - p3[2] = bmin[2]; - } - else - { - p3[0] = bmin[0]; - p3[2] = bmax[2]; - } - - break; - case 2: - p2[0] = bmin[0]; - p2[1] = bmin[1]; - - if ( dx > dy ) - { - p3[0] = bmax[0]; - p3[1] = bmin[1]; - } - else - { - p3[0] = bmin[0]; - p3[1] = bmax[1]; - } - - break; - } - -// callback->ConvexDebugTri(p1,p2,p3,0xFF0000); - - computePlane(p1,p2,p3,plane); - - return true; - -} - - -} diff --git a/extern/bullet/src/Extras/ConvexDecomposition/splitplane.h b/extern/bullet/src/Extras/ConvexDecomposition/splitplane.h deleted file mode 100644 index 26fe2e33ed28..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/splitplane.h +++ /dev/null @@ -1,59 +0,0 @@ -#ifndef SPLIT_PLANE_H - -#define SPLIT_PLANE_H - -//** Computes an 'optimal' split plane for the supplied mesh. -//** needs much improvement since it currently just splits along -//** the longest side of the AABB. -/*---------------------------------------------------------------------- - Copyright (c) 2004 Open Dynamics Framework Group - www.physicstools.org - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are permitted provided - that the following conditions are met: - - Redistributions of source code must retain the above copyright notice, this list of conditions - and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - Neither the name of the Open Dynamics Framework Group nor the names of its contributors may - be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER - IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -// http://codesuppository.blogspot.com -// -// mailto: jratcliff@infiniplex.net -// -// http://www.amillionpixels.us -// - - - -namespace ConvexDecomposition -{ - -class ConvexDecompInterface; - -bool computeSplitPlane(unsigned int vcount, - const float *vertices, - unsigned int tcount, - const unsigned int *indices, - ConvexDecompInterface *callback, - float *plane); - - -} - -#endif diff --git a/extern/bullet/src/Extras/ConvexDecomposition/vlookup.cpp b/extern/bullet/src/Extras/ConvexDecomposition/vlookup.cpp deleted file mode 100644 index 3b9e928ca09a..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/vlookup.cpp +++ /dev/null @@ -1,326 +0,0 @@ -#include "float_math.h" -#include -#include -#include -#include - -#pragma warning(disable:4786) - -#include -#include -#include - - -/*---------------------------------------------------------------------- - Copyright (c) 2004 Open Dynamics Framework Group - www.physicstools.org - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are permitted provided - that the following conditions are met: - - Redistributions of source code must retain the above copyright notice, this list of conditions - and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - Neither the name of the Open Dynamics Framework Group nor the names of its contributors may - be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER - IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -// http://codesuppository.blogspot.com -// -// mailto: jratcliff@infiniplex.net -// -// http://www.amillionpixels.us -// - -// CodeSnippet provided by John W. Ratcliff -// on March 23, 2006. -// -// mailto: jratcliff@infiniplex.net -// -// Personal website: http://jratcliffscarab.blogspot.com -// Coding Website: http://codesuppository.blogspot.com -// FundRaising Blog: http://amillionpixels.blogspot.com -// Fundraising site: http://www.amillionpixels.us -// New Temple Site: http://newtemple.blogspot.com -// -// This snippet shows how to 'hide' the complexity of -// the STL by wrapping some useful piece of functionality -// around a handful of discrete API calls. -// -// This API allows you to create an indexed triangle list -// from a collection of raw input triangles. Internally -// it uses an STL set to build the lookup table very rapidly. -// -// Here is how you would use it to build an indexed triangle -// list from a raw list of triangles. -// -// (1) create a 'VertexLookup' interface by calling -// -// VertexLook vl = Vl_createVertexLookup(); -// -// (2) For each vertice in each triangle call: -// -// unsigned int i1 = Vl_getIndex(vl,p1); -// unsigned int i2 = Vl_getIndex(vl,p2); -// unsigned int i3 = Vl_getIndex(vl,p3); -// -// save the 3 indices into your triangle list array. -// -// (3) Get the vertex array by calling: -// -// const float *vertices = Vl_getVertices(vl); -// -// (4) Get the number of vertices so you can copy them into -// your own buffer. -// unsigned int vcount = Vl_getVcount(vl); -// -// (5) Release the VertexLookup interface when you are done with it. -// Vl_releaseVertexLookup(vl); -// -// Teaches the following lessons: -// -// How to wrap the complexity of STL and C++ classes around a -// simple API interface. -// -// How to use an STL set and custom comparator operator for -// a complex data type. -// -// How to create a template class. -// -// How to achieve significant performance improvements by -// taking advantage of built in STL containers in just -// a few lines of code. -// -// You could easily modify this code to support other vertex -// formats with any number of interpolants. - - - - -#include "vlookup.h" - -namespace Vlookup -{ - -class VertexPosition -{ -public: - VertexPosition(void) { }; - VertexPosition(const float *p) - { - mPos[0] = p[0]; - mPos[1] = p[1]; - mPos[2] = p[2]; - }; - - void Set(int index,const float *pos) - { - const float * p = &pos[index*3]; - - mPos[0] = p[0]; - mPos[1] = p[1]; - mPos[2] = p[2]; - - }; - - float GetX(void) const { return mPos[0]; }; - float GetY(void) const { return mPos[1]; }; - float GetZ(void) const { return mPos[2]; }; - - float mPos[3]; -}; - -typedef std::vector< VertexPosition > VertexVector; - -struct Tracker -{ - VertexPosition mFind; // vertice to locate. - VertexVector *mList; - - Tracker() - { - mList = 0; - } - - void SetSearch(const VertexPosition& match,VertexVector *list) - { - mFind = match; - mList = list; - }; -}; - -struct VertexID -{ - int mID; - Tracker* mTracker; - - VertexID(int ID, Tracker* Tracker) - { - mID = ID; - mTracker = Tracker; - } -}; - -class VertexLess -{ -public: - - bool operator()(VertexID v1,VertexID v2) const; - -private: - const VertexPosition& Get(VertexID index) const - { - if ( index.mID == -1 ) return index.mTracker->mFind; - VertexVector &vlist = *index.mTracker->mList; - return vlist[index.mID]; - } -}; - -template class VertexPool -{ -public: - typedef std::set VertexSet; - typedef std::vector< Type > VertexVector; - - int getVertex(const Type& vtx) - { - mTracker.SetSearch(vtx,&mVtxs); - VertexSet::iterator found; - found = mVertSet.find( VertexID(-1,&mTracker) ); - if ( found != mVertSet.end() ) - { - return found->mID; - } - int idx = (int)mVtxs.size(); - mVtxs.push_back( vtx ); - mVertSet.insert( VertexID(idx,&mTracker) ); - return idx; - }; - - - const float * GetPos(int idx) const - { - return mVtxs[idx].mPos; - } - - const Type& Get(int idx) const - { - return mVtxs[idx]; - }; - - unsigned int GetSize(void) const - { - return mVtxs.size(); - }; - - void Clear(int reservesize) // clear the vertice pool. - { - mVertSet.clear(); - mVtxs.clear(); - mVtxs.reserve(reservesize); - }; - - const VertexVector& GetVertexList(void) const { return mVtxs; }; - - void Set(const Type& vtx) - { - mVtxs.push_back(vtx); - } - - unsigned int GetVertexCount(void) const - { - return mVtxs.size(); - }; - - - Type * getBuffer(void) - { - return &mVtxs[0]; - }; - -private: - VertexSet mVertSet; // ordered list. - VertexVector mVtxs; // set of vertices. - Tracker mTracker; -}; - - -bool VertexLess::operator()(VertexID v1,VertexID v2) const -{ - - const VertexPosition& a = Get(v1); - const VertexPosition& b = Get(v2); - - int ixA = (int) (a.GetX()*10000.0f); - int ixB = (int) (b.GetX()*10000.0f); - - if ( ixA < ixB ) return true; - if ( ixA > ixB ) return false; - - int iyA = (int) (a.GetY()*10000.0f); - int iyB = (int) (b.GetY()*10000.0f); - - if ( iyA < iyB ) return true; - if ( iyA > iyB ) return false; - - int izA = (int) (a.GetZ()*10000.0f); - int izB = (int) (b.GetZ()*10000.0f); - - if ( izA < izB ) return true; - if ( izA > izB ) return false; - - - return false; -} - - - - -} - -using namespace Vlookup; - -VertexLookup Vl_createVertexLookup(void) -{ - VertexLookup ret = new VertexPool< VertexPosition >; - return ret; -} - -void Vl_releaseVertexLookup(VertexLookup vlook) -{ - VertexPool< VertexPosition > *vp = (VertexPool< VertexPosition > *) vlook; - delete vp; -} - -unsigned int Vl_getIndex(VertexLookup vlook,const float *pos) // get index. -{ - VertexPool< VertexPosition > *vp = (VertexPool< VertexPosition > *) vlook; - VertexPosition p(pos); - return vp->getVertex(p); -} - -const float * Vl_getVertices(VertexLookup vlook) -{ - VertexPool< VertexPosition > *vp = (VertexPool< VertexPosition > *) vlook; - return vp->GetPos(0); -} - - -unsigned int Vl_getVcount(VertexLookup vlook) -{ - VertexPool< VertexPosition > *vp = (VertexPool< VertexPosition > *) vlook; - return vp->GetVertexCount(); -} diff --git a/extern/bullet/src/Extras/ConvexDecomposition/vlookup.h b/extern/bullet/src/Extras/ConvexDecomposition/vlookup.h deleted file mode 100644 index 1a6e0a9e2c7e..000000000000 --- a/extern/bullet/src/Extras/ConvexDecomposition/vlookup.h +++ /dev/null @@ -1,119 +0,0 @@ -#ifndef VLOOKUP_H - -#define VLOOKUP_H - - -/*---------------------------------------------------------------------- - Copyright (c) 2004 Open Dynamics Framework Group - www.physicstools.org - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are permitted provided - that the following conditions are met: - - Redistributions of source code must retain the above copyright notice, this list of conditions - and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - Neither the name of the Open Dynamics Framework Group nor the names of its contributors may - be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE INTEL OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER - IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------*/ - -// http://codesuppository.blogspot.com -// -// mailto: jratcliff@infiniplex.net -// -// http://www.amillionpixels.us -// - - -// CodeSnippet provided by John W. Ratcliff -// on March 23, 2006. -// -// mailto: jratcliff@infiniplex.net -// -// Personal website: http://jratcliffscarab.blogspot.com -// Coding Website: http://codesuppository.blogspot.com -// FundRaising Blog: http://amillionpixels.blogspot.com -// Fundraising site: http://www.amillionpixels.us -// New Temple Site: http://newtemple.blogspot.com -// -// This snippet shows how to 'hide' the complexity of -// the STL by wrapping some useful piece of functionality -// around a handful of discrete API calls. -// -// This API allows you to create an indexed triangle list -// from a collection of raw input triangles. Internally -// it uses an STL set to build the lookup table very rapidly. -// -// Here is how you would use it to build an indexed triangle -// list from a raw list of triangles. -// -// (1) create a 'VertexLookup' interface by calling -// -// VertexLook vl = Vl_createVertexLookup(); -// -// (2) For each vertice in each triangle call: -// -// unsigned int i1 = Vl_getIndex(vl,p1); -// unsigned int i2 = Vl_getIndex(vl,p2); -// unsigned int i3 = Vl_getIndex(vl,p3); -// -// save the 3 indices into your triangle list array. -// -// (3) Get the vertex array by calling: -// -// const float *vertices = Vl_getVertices(vl); -// -// (4) Get the number of vertices so you can copy them into -// your own buffer. -// unsigned int vcount = Vl_getVcount(vl); -// -// (5) Release the VertexLookup interface when you are done with it. -// Vl_releaseVertexLookup(vl); -// -// Teaches the following lessons: -// -// How to wrap the complexity of STL and C++ classes around a -// simple API interface. -// -// How to use an STL set and custom comparator operator for -// a complex data type. -// -// How to create a template class. -// -// How to achieve significant performance improvements by -// taking advantage of built in STL containers in just -// a few lines of code. -// -// You could easily modify this code to support other vertex -// formats with any number of interpolants. -// -// Hide C++ classes from the rest of your application by -// keeping them in the CPP and wrapping them in a namespace -// Uses an STL set to create an index table for a bunch of vertex positions -// used typically to re-index a collection of raw triangle data. - - -typedef void * VertexLookup; - -VertexLookup Vl_createVertexLookup(void); -void Vl_releaseVertexLookup(VertexLookup vlook); - -unsigned int Vl_getIndex(VertexLookup vlook,const float *pos); // get index. -const float * Vl_getVertices(VertexLookup vlook); -unsigned int Vl_getVcount(VertexLookup vlook); - - -#endif diff --git a/extern/bullet/src/Extras/GIMPACTUtils/CMakeLists.txt b/extern/bullet/src/Extras/GIMPACTUtils/CMakeLists.txt deleted file mode 100644 index c32a885dfb4f..000000000000 --- a/extern/bullet/src/Extras/GIMPACTUtils/CMakeLists.txt +++ /dev/null @@ -1,40 +0,0 @@ -INCLUDE_DIRECTORIES( -${BULLET_PHYSICS_SOURCE_DIR}/Extras/GIMPACT/include -${BULLET_PHYSICS_SOURCE_DIR}/src -${BULLET_PHYSICS_SOURCE_DIR}/Extras/GIMPACTUtils -${BULLET_PHYSICS_SOURCE_DIR}/Extras/ConvexDecomposition -) - -ADD_LIBRARY(GIMPACTUtils -btGImpactConvexDecompositionShape.cpp btGImpactConvexDecompositionShape.h -) -SET_TARGET_PROPERTIES(GIMPACTUtils PROPERTIES VERSION ${BULLET_VERSION}) -SET_TARGET_PROPERTIES(GIMPACTUtils PROPERTIES SOVERSION ${BULLET_VERSION}) - -IF (BUILD_SHARED_LIBS) - TARGET_LINK_LIBRARIES(GIMPACTUtils ConvexDecomposition BulletCollision) -ENDIF (BUILD_SHARED_LIBS) - -IF (INSTALL_EXTRA_LIBS) - IF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES) - #FILES_MATCHING requires CMake 2.6 - IF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5) - IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - INSTALL(TARGETS GIMPACTUtils DESTINATION .) - ELSE (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - INSTALL(TARGETS GIMPACTUtils - RUNTIME DESTINATION bin - LIBRARY DESTINATION lib${LIB_SUFFIX} - ARCHIVE DESTINATION lib${LIB_SUFFIX}) - INSTALL(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} -DESTINATION ${INCLUDE_INSTALL_DIR} FILES_MATCHING PATTERN "*.h" PATTERN -".svn" EXCLUDE PATTERN "CMakeFiles" EXCLUDE) - ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - ENDIF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5) - - IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - SET_TARGET_PROPERTIES(GIMPACTUtils PROPERTIES FRAMEWORK true) - SET_TARGET_PROPERTIES(GIMPACTUtils PROPERTIES PUBLIC_HEADER "btGImpactConvexDecompositionShape.h") - ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - ENDIF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES) -ENDIF (INSTALL_EXTRA_LIBS) diff --git a/extern/bullet/src/Extras/GIMPACTUtils/btGImpactConvexDecompositionShape.cpp b/extern/bullet/src/Extras/GIMPACTUtils/btGImpactConvexDecompositionShape.cpp deleted file mode 100644 index 5cdc32984755..000000000000 --- a/extern/bullet/src/Extras/GIMPACTUtils/btGImpactConvexDecompositionShape.cpp +++ /dev/null @@ -1,240 +0,0 @@ -/* -This source file is part of GIMPACT Library. - -For the latest info, see http://gimpact.sourceforge.net/ - -Copyright (c) 2007 Francisco Leon Najera. C.C. 80087371. -email: projectileman@yahoo.com - - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#include "btGImpactConvexDecompositionShape.h" -#include "BulletCollision/CollisionShapes/btConvexHullShape.h" - -#include "Extras/ConvexDecomposition/ConvexBuilder.h" - -class GIM_ConvexDecomposition : public ConvexDecomposition::ConvexDecompInterface -{ -protected: - btGImpactConvexDecompositionShape * m_compoundShape; - - btAlignedObjectArray m_convexShapes; - - -public: - int mBaseCount; - int mHullCount; - bool m_transformSubShapes; - - GIM_ConvexDecomposition(btGImpactConvexDecompositionShape * compoundShape,bool transformSubShapes) - { - mBaseCount = 0; - mHullCount = 0; - m_compoundShape = compoundShape; - m_transformSubShapes = transformSubShapes; - } - - virtual ~GIM_ConvexDecomposition() - { - int i; - for (i=0;i vertices; - - if(m_transformSubShapes) - { - - //const unsigned int *src = result.mHullIndices; - for (unsigned int i=0; isetMargin(m_compoundShape->getMargin()); - - if(m_transformSubShapes) - { - btTransform trans; - trans.setIdentity(); - trans.setOrigin(centroid); - - // add convex shape - - m_compoundShape->addChildShape(trans,convexShape); - } - else - { - btTransform trans; - trans.setIdentity(); - //trans.setOrigin(centroid); - - // add convex shape - - m_compoundShape->addChildShape(trans,convexShape); - - //m_compoundShape->addChildShape(convexShape); - } - } - - void processDecomposition(int part) - { - btGImpactMeshShapePart::TrimeshPrimitiveManager * trimeshInterface = - m_compoundShape->getTrimeshInterface(part); - - - trimeshInterface->lock(); - - //collect vertices - btAlignedObjectArray vertices; - vertices.reserve(trimeshInterface->get_vertex_count()*3); - - for(int vi = 0;viget_vertex_count();vi++) - { - btVector3 vec; - trimeshInterface->get_vertex(vi,vec); - vertices.push_back(vec[0]); - vertices.push_back(vec[1]); - vertices.push_back(vec[2]); - } - - - //collect indices - btAlignedObjectArray indices; - indices.reserve(trimeshInterface->get_primitive_count()*3); - - - for(int i = 0;iget_primitive_count();i++) - { - unsigned int i0, i1,i2; - trimeshInterface->get_indices(i,i0,i1,i2); - indices.push_back(i0); - indices.push_back(i1); - indices.push_back(i2); - } - - trimeshInterface->unlock(); - - - - unsigned int depth = 5; - float cpercent = 5; - float ppercent = 15; - unsigned int maxv = 16; - float skinWidth = 0.0f; - - - ConvexDecomposition::DecompDesc desc; - desc.mVcount = trimeshInterface->get_vertex_count(); - desc.mVertices = &vertices[0]; - desc.mTcount = trimeshInterface->get_primitive_count(); - desc.mIndices = &indices[0]; - desc.mDepth = depth; - desc.mCpercent = cpercent; - desc.mPpercent = ppercent; - desc.mMaxVertices = maxv; - desc.mSkinWidth = skinWidth; - desc.mCallback = this; - - //convexDecomposition.performConvexDecomposition(desc); - - ConvexBuilder cb(desc.mCallback); - cb.process(desc); - } - - - - -}; - - - -void btGImpactConvexDecompositionShape::buildConvexDecomposition(bool transformSubShapes) -{ - - m_decomposition = new GIM_ConvexDecomposition(this,transformSubShapes); - - int part_count = m_trimeshInterfaces.size(); - for (int i = 0;iprocessDecomposition(i); - } - - postUpdate(); -} - -btGImpactConvexDecompositionShape::~btGImpactConvexDecompositionShape() -{ - delete m_decomposition; -} -void btGImpactConvexDecompositionShape::processAllTriangles(btTriangleCallback* callback,const btVector3& aabbMin,const btVector3& aabbMax) const -{ - - int part_count = m_trimeshInterfaces.size(); - for (int part = 0;part(ptr); - - trimeshInterface->lock(); - - btPrimitiveTriangle triangle; - - - int i = trimeshInterface->get_primitive_count(); - while(i--) - { - trimeshInterface->get_primitive_triangle(i,triangle); - callback->processTriangle(triangle.m_vertices,part,i); - } - - trimeshInterface->unlock(); - } - - -} diff --git a/extern/bullet/src/Extras/GIMPACTUtils/btGImpactConvexDecompositionShape.h b/extern/bullet/src/Extras/GIMPACTUtils/btGImpactConvexDecompositionShape.h deleted file mode 100644 index 4710861f3e0f..000000000000 --- a/extern/bullet/src/Extras/GIMPACTUtils/btGImpactConvexDecompositionShape.h +++ /dev/null @@ -1,87 +0,0 @@ -/*! \file btGImpactConvexDecompositionShape.h -\author Francisco León Nájera -*/ -/* -This source file is part of GIMPACT Library. - -For the latest info, see http://gimpact.sourceforge.net/ - -Copyright (c) 2007 Francisco Leon Najera. C.C. 80087371. -email: projectileman@yahoo.com - - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#ifndef GIMPACT_CONVEX_DECOMPOSITION_SHAPE_H -#define GIMPACT_CONVEX_DECOMPOSITION_SHAPE_H - - -#include "BulletCollision/Gimpact/btGImpactShape.h" // box tree class - - - -//! This class creates a decomposition from a trimesh. -/*! - -*/ -class btGImpactConvexDecompositionShape : public btGImpactCompoundShape -{ -protected: - btAlignedObjectArray m_trimeshInterfaces; - - class GIM_ConvexDecomposition* m_decomposition; - - void buildConvexDecomposition(bool transformSubShapes); -public: - - btGImpactConvexDecompositionShape( - btStridingMeshInterface * meshInterface, - const btVector3 & mesh_scale, - btScalar margin = btScalar(0.01),bool children_has_transform = true) - :btGImpactCompoundShape(children_has_transform) - { - - m_collisionMargin = margin; - - btGImpactMeshShapePart::TrimeshPrimitiveManager triInterface; - triInterface.m_meshInterface = meshInterface; - triInterface.m_scale = mesh_scale; - triInterface.m_margin = btScalar(1.0); - - //add parts - int part_count = meshInterface->getNumSubParts(); - for (int i=0;i< part_count;i++ ) - { - triInterface.m_part = i; - m_trimeshInterfaces.push_back(triInterface); - } - - m_decomposition = 0; - - buildConvexDecomposition(children_has_transform); - } - - virtual ~btGImpactConvexDecompositionShape(); - - SIMD_FORCE_INLINE btGImpactMeshShapePart::TrimeshPrimitiveManager * getTrimeshInterface(int part) - { - return &m_trimeshInterfaces[part]; - } - - virtual void processAllTriangles(btTriangleCallback* callback,const btVector3& aabbMin,const btVector3& aabbMax) const; - -}; - - - - -#endif //GIMPACT_MESH_SHAPE_H diff --git a/extern/bullet/src/Extras/HACD/CMakeLists.txt b/extern/bullet/src/Extras/HACD/CMakeLists.txt deleted file mode 100644 index a91d1173cdc8..000000000000 --- a/extern/bullet/src/Extras/HACD/CMakeLists.txt +++ /dev/null @@ -1,55 +0,0 @@ -INCLUDE_DIRECTORIES( - ${BULLET_PHYSICS_SOURCE_DIR}/Extras/HACD -) - -SET(HACD_SRCS - hacdGraph.cpp - hacdHACD.cpp - hacdICHull.cpp - hacdManifoldMesh.cpp -) - -SET(HACD_HDRS - hacdCircularList.h - hacdGraph.h - hacdHACD.h - hacdICHull.h - hacdManifoldMesh.h - hacdVector.h - hacdVersion.h - hacdCircularList.inl - hacdVector.inl -) - -ADD_LIBRARY(HACD ${HACD_SRCS} ${HACD_HDRS}) -SET_TARGET_PROPERTIES(HACD PROPERTIES VERSION ${BULLET_VERSION}) -SET_TARGET_PROPERTIES(HACD PROPERTIES SOVERSION ${BULLET_VERSION}) - -#IF (BUILD_SHARED_LIBS) -# TARGET_LINK_LIBRARIES(HACD BulletCollision LinearMath) -#ENDIF (BUILD_SHARED_LIBS) - -IF (INSTALL_EXTRA_LIBS) - IF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES) - #FILES_MATCHING requires CMake 2.6 - IF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5) - IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - INSTALL(TARGETS HACD DESTINATION .) - ELSE (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - INSTALL(TARGETS HACD - RUNTIME DESTINATION bin - LIBRARY DESTINATION lib${LIB_SUFFIX} - ARCHIVE DESTINATION lib${LIB_SUFFIX}) - - INSTALL(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} - DESTINATION ${INCLUDE_INSTALL_DIR} FILES_MATCHING PATTERN "*.h" PATTERN "*.inl" PATTERN - ".svn" EXCLUDE PATTERN "CMakeFiles" EXCLUDE) - ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - ENDIF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5) - - IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - SET_TARGET_PROPERTIES(HACD PROPERTIES FRAMEWORK true) - SET_TARGET_PROPERTIES(HACD PROPERTIES PUBLIC_HEADER "${HACD_HDRS}") - ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - ENDIF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES) -ENDIF (INSTALL_EXTRA_LIBS) diff --git a/extern/bullet/src/Extras/HACD/hacdCircularList.h b/extern/bullet/src/Extras/HACD/hacdCircularList.h deleted file mode 100644 index a13394cd65dd..000000000000 --- a/extern/bullet/src/Extras/HACD/hacdCircularList.h +++ /dev/null @@ -1,80 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) - All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#pragma once -#ifndef HACD_CIRCULAR_LIST_H -#define HACD_CIRCULAR_LIST_H -#include -#include "hacdVersion.h" -namespace HACD -{ - //! CircularListElement class. - template < typename T > class CircularListElement - { - public: - T & GetData() { return m_data; } - const T & GetData() const { return m_data; } - CircularListElement * & GetNext() { return m_next; } - CircularListElement * & GetPrev() { return m_prev; } - const CircularListElement * & GetNext() const { return m_next; } - const CircularListElement * & GetPrev() const { return m_prev; } - //! Constructor - CircularListElement(const T & data) {m_data = data;} - CircularListElement(void){} - //! Destructor - ~CircularListElement(void){} - private: - T m_data; - CircularListElement * m_next; - CircularListElement * m_prev; - - CircularListElement(const CircularListElement & rhs); - }; - - - //! CircularList class. - template < typename T > class CircularList - { - public: - CircularListElement * & GetHead() { return m_head;} - const CircularListElement * GetHead() const { return m_head;} - bool IsEmpty() const { return (m_size == 0);} - size_t GetSize() const { return m_size; } - const T & GetData() const { return m_head->GetData(); } - T & GetData() { return m_head->GetData();} - bool Delete() ; - bool Delete(CircularListElement * element); - CircularListElement * Add(const T * data = 0); - CircularListElement * Add(const T & data); - bool Next(); - bool Prev(); - void Clear() { while(Delete());}; - const CircularList& operator=(const CircularList& rhs); - //! Constructor - CircularList() - { - m_head = 0; - m_size = 0; - } - CircularList(const CircularList& rhs); - //! Destructor - virtual ~CircularList(void) {Clear();}; - private: - CircularListElement * m_head; //!< a pointer to the head of the circular list - size_t m_size; //!< number of element in the circular list - - }; -} -#include "hacdCircularList.inl" -#endif diff --git a/extern/bullet/src/Extras/HACD/hacdCircularList.inl b/extern/bullet/src/Extras/HACD/hacdCircularList.inl deleted file mode 100644 index 471f9ed44983..000000000000 --- a/extern/bullet/src/Extras/HACD/hacdCircularList.inl +++ /dev/null @@ -1,163 +0,0 @@ -#pragma once -#ifndef HACD_CIRCULAR_LIST_INL -#define HACD_CIRCULAR_LIST_INL -#include -#include "hacdVersion.h" -namespace HACD -{ - template < typename T > - inline bool CircularList::Delete(CircularListElement * element) - { - if (!element) - { - return false; - } - if (m_size > 1) - { - CircularListElement * next = element->GetNext(); - CircularListElement * prev = element->GetPrev(); - delete element; - m_size--; - if (element == m_head) - { - m_head = next; - } - next->GetPrev() = prev; - prev->GetNext() = next; - return true; - } - else if (m_size == 1) - { - delete m_head; - m_size--; - m_head = 0; - return true; - } - else - { - return false; - } - } - - template < typename T > - inline bool CircularList::Delete() - { - if (m_size > 1) - { - CircularListElement * next = m_head->GetNext(); - CircularListElement * prev = m_head->GetPrev(); - delete m_head; - m_size--; - m_head = next; - next->GetPrev() = prev; - prev->GetNext() = next; - return true; - } - else if (m_size == 1) - { - delete m_head; - m_size--; - m_head = 0; - return true; - } - else - { - return false; - } - } - template < typename T > - inline CircularListElement * CircularList::Add(const T * data) - { - if (m_size == 0) - { - if (data) - { - m_head = new CircularListElement(*data); - } - else - { - m_head = new CircularListElement(); - } - m_head->GetNext() = m_head->GetPrev() = m_head; - } - else - { - CircularListElement * next = m_head->GetNext(); - CircularListElement * element = m_head; - if (data) - { - m_head = new CircularListElement(*data); - } - else - { - m_head = new CircularListElement; - } - m_head->GetNext() = next; - m_head->GetPrev() = element; - element->GetNext() = m_head; - next->GetPrev() = m_head; - } - m_size++; - return m_head; - } - template < typename T > - inline CircularListElement * CircularList::Add(const T & data) - { - const T * pData = &data; - return Add(pData); - } - template < typename T > - inline bool CircularList::Next() - { - if (m_size == 0) - { - return false; - } - m_head = m_head->GetNext(); - return true; - } - template < typename T > - inline bool CircularList::Prev() - { - if (m_size == 0) - { - return false; - } - m_head = m_head->GetPrev(); - return true; - } - template < typename T > - inline CircularList::CircularList(const CircularList& rhs) - { - if (rhs.m_size > 0) - { - CircularListElement * current = rhs.m_head; - do - { - current = current->GetNext(); - Add(current->GetData()); - } - while ( current != rhs.m_head ); - } - } - template < typename T > - inline const CircularList& CircularList::operator=(const CircularList& rhs) - { - if (&rhs != this) - { - Clear(); - if (rhs.m_size > 0) - { - CircularListElement * current = rhs.m_head; - do - { - current = current->GetNext(); - Add(current->GetData()); - } - while ( current != rhs.m_head ); - } - } - return (*this); - } -} -#endif diff --git a/extern/bullet/src/Extras/HACD/hacdGraph.cpp b/extern/bullet/src/Extras/HACD/hacdGraph.cpp deleted file mode 100644 index 4204f2d67764..000000000000 --- a/extern/bullet/src/Extras/HACD/hacdGraph.cpp +++ /dev/null @@ -1,292 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) - All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#include "hacdGraph.h" -namespace HACD -{ - - GraphEdge::GraphEdge() - { - m_convexHull = 0; - m_v1 = -1; - m_v2 = -1; - m_name = -1; - m_error = 0; - m_surf = 0; - m_perimeter = 0; - m_concavity = 0; - m_volume = 0; - m_deleted = false; - } - - GraphVertex::GraphVertex() - { - m_convexHull = 0; - m_name = -1; - m_cc = -1; - m_error = 0; - m_surf = 0; - m_perimeter = 0; - m_concavity = 0; - m_volume = 0; - m_deleted = false; - } - - bool GraphVertex::DeleteEdge(long name) - { - std::set::iterator it = m_edges.find(name); - if (it != m_edges.end() ) - { - m_edges.erase(it); - return true; - } - return false; - } - - Graph::Graph() - { - m_nV = 0; - m_nE = 0; - m_nCCs = 0; - } - - Graph::~Graph() - { - } - - void Graph::Allocate(size_t nV, size_t nE) - { - m_nV = nV; - m_edges.reserve(nE); - m_vertices.resize(nV); - for(size_t i = 0; i < nV; i++) - { - m_vertices[i].m_name = static_cast(i); - } - } - - long Graph::AddVertex() - { - size_t name = m_vertices.size(); - m_vertices.resize(name+1); - m_vertices[name].m_name = static_cast(name); - m_nV++; - return static_cast(name); - } - - long Graph::AddEdge(long v1, long v2) - { - size_t name = m_edges.size(); - m_edges.push_back(GraphEdge()); - m_edges[name].m_name = static_cast(name); - m_edges[name].m_v1 = v1; - m_edges[name].m_v2 = v2; - m_vertices[v1].AddEdge(static_cast(name)); - m_vertices[v2].AddEdge(static_cast(name)); - m_nE++; - return static_cast(name); - } - - bool Graph::DeleteEdge(long name) - { - if (name < static_cast(m_edges.size())) - { - long v1 = m_edges[name].m_v1; - long v2 = m_edges[name].m_v2; - m_edges[name].m_deleted = true; - m_vertices[v1].DeleteEdge(name); - m_vertices[v2].DeleteEdge(name); - delete m_edges[name].m_convexHull; - m_edges[name].m_distPoints.clear(); - m_edges[name].m_boudaryEdges.clear(); - m_edges[name].m_convexHull = 0; - m_nE--; - return true; - } - return false; - } - bool Graph::DeleteVertex(long name) - { - if (name < static_cast(m_vertices.size())) - { - m_vertices[name].m_deleted = true; - m_vertices[name].m_edges.clear(); - m_vertices[name].m_ancestors = std::vector(); - delete m_vertices[name].m_convexHull; - m_vertices[name].m_distPoints.clear(); - m_vertices[name].m_boudaryEdges.clear(); - m_vertices[name].m_convexHull = 0; - m_nV--; - return true; - } - return false; - } - bool Graph::EdgeCollapse(long v1, long v2) - { - long edgeToDelete = GetEdgeID(v1, v2); - if (edgeToDelete >= 0) - { - // delete the edge (v1, v2) - DeleteEdge(edgeToDelete); - // add v2 to v1 ancestors - m_vertices[v1].m_ancestors.push_back(v2); - // add v2's ancestors to v1's ancestors - m_vertices[v1].m_ancestors.insert(m_vertices[v1].m_ancestors.begin(), - m_vertices[v2].m_ancestors.begin(), - m_vertices[v2].m_ancestors.end()); - // update adjacency information - std::set & v1Edges = m_vertices[v1].m_edges; - std::set::const_iterator ed(m_vertices[v2].m_edges.begin()); - std::set::const_iterator itEnd(m_vertices[v2].m_edges.end()); - long b = -1; - for(; ed != itEnd; ++ed) - { - if (m_edges[*ed].m_v1 == v2) - { - b = m_edges[*ed].m_v2; - } - else - { - b = m_edges[*ed].m_v1; - } - if (GetEdgeID(v1, b) >= 0) - { - m_edges[*ed].m_deleted = true; - m_vertices[b].DeleteEdge(*ed); - m_nE--; - } - else - { - m_edges[*ed].m_v1 = v1; - m_edges[*ed].m_v2 = b; - v1Edges.insert(*ed); - } - } - // delete the vertex v2 - DeleteVertex(v2); - return true; - } - return false; - } - - long Graph::GetEdgeID(long v1, long v2) const - { - if (v1 < static_cast(m_vertices.size()) && !m_vertices[v1].m_deleted) - { - std::set::const_iterator ed(m_vertices[v1].m_edges.begin()); - std::set::const_iterator itEnd(m_vertices[v1].m_edges.end()); - for(; ed != itEnd; ++ed) - { - if ( (m_edges[*ed].m_v1 == v2) || - (m_edges[*ed].m_v2 == v2) ) - { - return m_edges[*ed].m_name; - } - } - } - return -1; - } - - void Graph::Print() const - { - std::cout << "-----------------------------" << std::endl; - std::cout << "vertices (" << m_nV << ")" << std::endl; - for (size_t v = 0; v < m_vertices.size(); ++v) - { - const GraphVertex & currentVertex = m_vertices[v]; - if (!m_vertices[v].m_deleted) - { - - std::cout << currentVertex.m_name << "\t"; - std::set::const_iterator ed(currentVertex.m_edges.begin()); - std::set::const_iterator itEnd(currentVertex.m_edges.end()); - for(; ed != itEnd; ++ed) - { - std::cout << "(" << m_edges[*ed].m_v1 << "," << m_edges[*ed].m_v2 << ") "; - } - std::cout << std::endl; - } - } - - std::cout << "vertices (" << m_nE << ")" << std::endl; - for (size_t e = 0; e < m_edges.size(); ++e) - { - const GraphEdge & currentEdge = m_edges[e]; - if (!m_edges[e].m_deleted) - { - std::cout << currentEdge.m_name << "\t(" - << m_edges[e].m_v1 << "," - << m_edges[e].m_v2 << ") "<< std::endl; - } - } - } - void Graph::Clear() - { - m_vertices.clear(); - m_edges.clear(); - m_nV = 0; - m_nE = 0; - } - - long Graph::ExtractCCs() - { - // all CCs to -1 - for (size_t v = 0; v < m_vertices.size(); ++v) - { - if (!m_vertices[v].m_deleted) - { - m_vertices[v].m_cc = -1; - } - } - - // we get the CCs - m_nCCs = 0; - long v2 = -1; - std::vector temp; - for (size_t v = 0; v < m_vertices.size(); ++v) - { - if (!m_vertices[v].m_deleted && m_vertices[v].m_cc == -1) - { - m_vertices[v].m_cc = static_cast(m_nCCs); - temp.clear(); - temp.push_back(m_vertices[v].m_name); - while (temp.size()) - { - long vertex = temp[temp.size()-1]; - temp.pop_back(); - std::set::const_iterator ed(m_vertices[vertex].m_edges.begin()); - std::set::const_iterator itEnd(m_vertices[vertex].m_edges.end()); - for(; ed != itEnd; ++ed) - { - if (m_edges[*ed].m_v1 == vertex) - { - v2 = m_edges[*ed].m_v2; - } - else - { - v2 = m_edges[*ed].m_v1; - } - if ( !m_vertices[v2].m_deleted && m_vertices[v2].m_cc == -1) - { - m_vertices[v2].m_cc = static_cast(m_nCCs); - temp.push_back(v2); - } - } - } - m_nCCs++; - } - } - return static_cast(m_nCCs); - } -} diff --git a/extern/bullet/src/Extras/HACD/hacdGraph.h b/extern/bullet/src/Extras/HACD/hacdGraph.h deleted file mode 100644 index 9b64aac60d3f..000000000000 --- a/extern/bullet/src/Extras/HACD/hacdGraph.h +++ /dev/null @@ -1,120 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) - All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#pragma once -#ifndef HACD_GRAPH_H -#define HACD_GRAPH_H -#include "hacdVersion.h" -#include "hacdVector.h" -#include "hacdICHull.h" -#include -#include -#include - -namespace HACD -{ - class GraphVertex; - class GraphEdge; - class Graph; - class HACD; - - class GraphVertex - { - public: - bool AddEdge(long name) - { - m_edges.insert(name); - return true; - } - bool DeleteEdge(long name); - GraphVertex(); - ~GraphVertex(){ delete m_convexHull;}; - private: - long m_name; - long m_cc; - std::set m_edges; - bool m_deleted; - std::vector m_ancestors; - std::map m_distPoints; - - Real m_error; - double m_surf; - double m_volume; - double m_perimeter; - double m_concavity; - ICHull * m_convexHull; - std::set m_boudaryEdges; - - - friend class GraphEdge; - friend class Graph; - friend class HACD; - }; - - class GraphEdge - { - public: - GraphEdge(); - ~GraphEdge(){delete m_convexHull;}; - private: - long m_name; - long m_v1; - long m_v2; - std::map m_distPoints; - Real m_error; - double m_surf; - double m_volume; - double m_perimeter; - double m_concavity; - ICHull * m_convexHull; - std::set m_boudaryEdges; - bool m_deleted; - - - - friend class GraphVertex; - friend class Graph; - friend class HACD; - }; - - class Graph - { - public: - size_t GetNEdges() const { return m_nE;} - size_t GetNVertices() const { return m_nV;} - bool EdgeCollapse(long v1, long v2); - long AddVertex(); - long AddEdge(long v1, long v2); - bool DeleteEdge(long name); - bool DeleteVertex(long name); - long GetEdgeID(long v1, long v2) const; - void Clear(); - void Print() const; - long ExtractCCs(); - - Graph(); - virtual ~Graph(); - void Allocate(size_t nV, size_t nE); - - private: - size_t m_nCCs; - size_t m_nV; - size_t m_nE; - std::vector m_edges; - std::vector m_vertices; - - friend class HACD; - }; -} -#endif diff --git a/extern/bullet/src/Extras/HACD/hacdHACD.cpp b/extern/bullet/src/Extras/HACD/hacdHACD.cpp deleted file mode 100644 index 5c2edf217fb0..000000000000 --- a/extern/bullet/src/Extras/HACD/hacdHACD.cpp +++ /dev/null @@ -1,851 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) - All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#ifndef _CRT_SECURE_NO_WARNINGS -#define _CRT_SECURE_NO_WARNINGS -#endif //_CRT_SECURE_NO_WARNINGS - -#include -#include "hacdGraph.h" -#include "hacdHACD.h" -#include "hacdICHull.h" -#include -#include -#include -#include -#include "assert.h" - -bool gCancelRequest=false; -namespace HACD -{ - double HACD::Concavity(ICHull & ch, std::map & distPoints) - { - double concavity = 0.0; - double distance = 0.0; - std::map::iterator itDP(distPoints.begin()); - std::map::iterator itDPEnd(distPoints.end()); - for(; itDP != itDPEnd; ++itDP) - { - if (!(itDP->second).m_computed) - { - if (itDP->first >= 0) - { - distance = ch.ComputeDistance(itDP->first, m_points[itDP->first], m_normals[itDP->first], (itDP->second).m_computed, true); - } - else - { - distance = ch.ComputeDistance(itDP->first, m_facePoints[-itDP->first-1], m_faceNormals[-itDP->first-1], (itDP->second).m_computed, true); - } - } - else - { - distance = (itDP->second).m_dist; - } - if (concavity < distance) - { - concavity = distance; - } - } - return concavity; - } - - void HACD::CreateGraph() - { - // vertex to triangle adjacency information - std::vector< std::set > vertexToTriangles; - vertexToTriangles.resize(m_nPoints); - for(size_t t = 0; t < m_nTriangles; ++t) - { - vertexToTriangles[m_triangles[t].X()].insert(static_cast(t)); - vertexToTriangles[m_triangles[t].Y()].insert(static_cast(t)); - vertexToTriangles[m_triangles[t].Z()].insert(static_cast(t)); - } - - m_graph.Clear(); - m_graph.Allocate(m_nTriangles, 5 * m_nTriangles); - unsigned long long tr1[3]; - unsigned long long tr2[3]; - long i1, j1, k1, i2, j2, k2; - long t1, t2; - for (size_t v = 0; v < m_nPoints; v++) - { - std::set::const_iterator it1(vertexToTriangles[v].begin()), itEnd(vertexToTriangles[v].end()); - for(; it1 != itEnd; ++it1) - { - t1 = *it1; - i1 = m_triangles[t1].X(); - j1 = m_triangles[t1].Y(); - k1 = m_triangles[t1].Z(); - tr1[0] = GetEdgeIndex(i1, j1); - tr1[1] = GetEdgeIndex(j1, k1); - tr1[2] = GetEdgeIndex(k1, i1); - std::set::const_iterator it2(it1); - for(++it2; it2 != itEnd; ++it2) - { - t2 = *it2; - i2 = m_triangles[t2].X(); - j2 = m_triangles[t2].Y(); - k2 = m_triangles[t2].Z(); - tr2[0] = GetEdgeIndex(i2, j2); - tr2[1] = GetEdgeIndex(j2, k2); - tr2[2] = GetEdgeIndex(k2, i2); - int shared = 0; - for(int i = 0; i < 3; ++i) - { - for(int j = 0; j < 3; ++j) - { - if (tr1[i] == tr2[j]) - { - shared++; - } - } - } - if (shared == 1) // two triangles are connected if they share exactly one edge - { - m_graph.AddEdge(t1, t2); - } - } - } - } - if (m_ccConnectDist >= 0.0) - { - m_graph.ExtractCCs(); - if (m_graph.m_nCCs > 1) - { - std::vector< std::set > cc2V; - cc2V.resize(m_graph.m_nCCs); - long cc; - for(size_t t = 0; t < m_nTriangles; ++t) - { - cc = m_graph.m_vertices[t].m_cc; - cc2V[cc].insert(m_triangles[t].X()); - cc2V[cc].insert(m_triangles[t].Y()); - cc2V[cc].insert(m_triangles[t].Z()); - } - - for(size_t cc1 = 0; cc1 < m_graph.m_nCCs; ++cc1) - { - for(size_t cc2 = cc1+1; cc2 < m_graph.m_nCCs; ++cc2) - { - std::set::const_iterator itV1(cc2V[cc1].begin()), itVEnd1(cc2V[cc1].end()); - for(; itV1 != itVEnd1; ++itV1) - { - double distC1C2 = std::numeric_limits::max(); - double dist; - t1 = -1; - t2 = -1; - std::set::const_iterator itV2(cc2V[cc2].begin()), itVEnd2(cc2V[cc2].end()); - for(; itV2 != itVEnd2; ++itV2) - { - dist = (m_points[*itV1] - m_points[*itV2]).GetNorm(); - if (dist < distC1C2) - { - distC1C2 = dist; - t1 = *vertexToTriangles[*itV1].begin(); - - std::set::const_iterator it2(vertexToTriangles[*itV2].begin()), - it2End(vertexToTriangles[*itV2].end()); - t2 = -1; - for(; it2 != it2End; ++it2) - { - if (*it2 != t1) - { - t2 = *it2; - break; - } - } - } - } - if (distC1C2 <= m_ccConnectDist && t1 > 0 && t2 > 0) - { - - m_graph.AddEdge(t1, t2); - } - } - } - } - } - } - } - void HACD::InitializeDualGraph() - { - long i, j, k; - Vec3 u, v, w, normal; - delete [] m_normals; - m_normals = new Vec3[m_nPoints]; - if (m_addFacesPoints) - { - delete [] m_facePoints; - delete [] m_faceNormals; - m_facePoints = new Vec3[m_nTriangles]; - m_faceNormals = new Vec3[m_nTriangles]; - } - memset(m_normals, 0, sizeof(Vec3) * m_nPoints); - for(unsigned long f = 0; f < m_nTriangles; f++) - { - if (m_callBack) (*m_callBack)("+ InitializeDualGraph\n", f, m_nTriangles, 0); - - if (gCancelRequest) - return; - - i = m_triangles[f].X(); - j = m_triangles[f].Y(); - k = m_triangles[f].Z(); - - m_graph.m_vertices[f].m_distPoints[i].m_distOnly = false; - m_graph.m_vertices[f].m_distPoints[j].m_distOnly = false; - m_graph.m_vertices[f].m_distPoints[k].m_distOnly = false; - - ICHull * ch = new ICHull; - m_graph.m_vertices[f].m_convexHull = ch; - ch->AddPoint(m_points[i], i); - ch->AddPoint(m_points[j], j); - ch->AddPoint(m_points[k], k); - ch->SetDistPoints(&m_graph.m_vertices[f].m_distPoints); - - u = m_points[j] - m_points[i]; - v = m_points[k] - m_points[i]; - w = m_points[k] - m_points[j]; - normal = u ^ v; - - m_normals[i] += normal; - m_normals[j] += normal; - m_normals[k] += normal; - - m_graph.m_vertices[f].m_surf = normal.GetNorm(); - m_graph.m_vertices[f].m_perimeter = u.GetNorm() + v.GetNorm() + w.GetNorm(); - - normal.Normalize(); - - m_graph.m_vertices[f].m_boudaryEdges.insert(GetEdgeIndex(i,j)); - m_graph.m_vertices[f].m_boudaryEdges.insert(GetEdgeIndex(j,k)); - m_graph.m_vertices[f].m_boudaryEdges.insert(GetEdgeIndex(k,i)); - if(m_addFacesPoints) - { - m_faceNormals[f] = normal; - m_facePoints[f] = (m_points[i] + m_points[j] + m_points[k]) / 3.0; - m_graph.m_vertices[f].m_distPoints[-static_cast(f)-1].m_distOnly = true; - } - if (m_addExtraDistPoints) - {// we need a kd-tree structure to accelerate this part! - long i1, j1, k1; - Vec3 u1, v1, normal1; - normal = -normal; - double distance = 0.0; - double distMin = 0.0; - size_t faceIndex = m_nTriangles; - Vec3 seedPoint((m_points[i] + m_points[j] + m_points[k]) / 3.0); - long nhit = 0; - for(size_t f1 = 0; f1 < m_nTriangles; f1++) - { - i1 = m_triangles[f1].X(); - j1 = m_triangles[f1].Y(); - k1 = m_triangles[f1].Z(); - u1 = m_points[j1] - m_points[i1]; - v1 = m_points[k1] - m_points[i1]; - normal1 = (u1 ^ v1); - if (normal * normal1 > 0.0) - { - nhit = IntersectRayTriangle(Vec3(seedPoint.X(), seedPoint.Y(), seedPoint.Z()), - Vec3(normal.X(), normal.Y(), normal.Z()), - Vec3(m_points[i1].X(), m_points[i1].Y(), m_points[i1].Z()), - Vec3(m_points[j1].X(), m_points[j1].Y(), m_points[j1].Z()), - Vec3(m_points[k1].X(), m_points[k1].Y(), m_points[k1].Z()), - distance); - if ((nhit==1) && ((distMin > distance) || (faceIndex == m_nTriangles))) - { - distMin = distance; - faceIndex = f1; - } - - } - } - if (faceIndex < m_nTriangles ) - { - i1 = m_triangles[faceIndex].X(); - j1 = m_triangles[faceIndex].Y(); - k1 = m_triangles[faceIndex].Z(); - m_graph.m_vertices[f].m_distPoints[i1].m_distOnly = true; - m_graph.m_vertices[f].m_distPoints[j1].m_distOnly = true; - m_graph.m_vertices[f].m_distPoints[k1].m_distOnly = true; - if (m_addFacesPoints) - { - m_graph.m_vertices[f].m_distPoints[-static_cast(faceIndex)-1].m_distOnly = true; - } - } - } - } - for (size_t v = 0; v < m_nPoints; v++) - { - m_normals[v].Normalize(); - } - } - - void HACD::NormalizeData() - { - if (m_nPoints == 0) - { - return; - } - m_barycenter = m_points[0]; - Vec3 min = m_points[0]; - Vec3 max = m_points[0]; - Real x, y, z; - for (size_t v = 1; v < m_nPoints ; v++) - { - m_barycenter += m_points[v]; - x = m_points[v].X(); - y = m_points[v].Y(); - z = m_points[v].Z(); - if ( x < min.X()) min.X() = x; - else if ( x > max.X()) max.X() = x; - if ( y < min.Y()) min.Y() = y; - else if ( y > max.Y()) max.Y() = y; - if ( z < min.Z()) min.Z() = z; - else if ( z > max.Z()) max.Z() = z; - } - m_barycenter /= static_cast(m_nPoints); - m_diag = (max-min).GetNorm(); - const Real invDiag = static_cast(2.0 * m_scale / m_diag); - if (m_diag != 0.0) - { - for (size_t v = 0; v < m_nPoints ; v++) - { - m_points[v] = (m_points[v] - m_barycenter) * invDiag; - } - } - } - void HACD::DenormalizeData() - { - if (m_nPoints == 0) - { - return; - } - if (m_diag != 0.0) - { - const Real diag = static_cast(m_diag / (2.0 * m_scale)); - for (size_t v = 0; v < m_nPoints ; v++) - { - m_points[v] = m_points[v] * diag + m_barycenter; - } - } - } - HACD::HACD(void) - { - m_convexHulls = 0; - m_triangles = 0; - m_points = 0; - m_normals = 0; - m_nTriangles = 0; - m_nPoints = 0; - m_nClusters = 0; - m_concavity = 0.0; - m_diag = 1.0; - m_barycenter = Vec3(0.0, 0.0,0.0); - m_alpha = 0.1; - m_beta = 0.1; - m_nVerticesPerCH = 30; - m_callBack = 0; - m_addExtraDistPoints = false; - m_addNeighboursDistPoints = false; - m_scale = 1000.0; - m_partition = 0; - m_nMinClusters = 3; - m_facePoints = 0; - m_faceNormals = 0; - m_ccConnectDist = 30; - } - HACD::~HACD(void) - { - delete [] m_normals; - delete [] m_convexHulls; - delete [] m_partition; - delete [] m_facePoints; - delete [] m_faceNormals; - } - int iteration = 0; - void HACD::ComputeEdgeCost(size_t e) - { - GraphEdge & gE = m_graph.m_edges[e]; - long v1 = gE.m_v1; - long v2 = gE.m_v2; - - if (m_graph.m_vertices[v2].m_distPoints.size()>m_graph.m_vertices[v1].m_distPoints.size()) - { - gE.m_v1 = v2; - gE.m_v2 = v1; - //std::swap(v1, v2); - std::swap(v1, v2); - } - GraphVertex & gV1 = m_graph.m_vertices[v1]; - GraphVertex & gV2 = m_graph.m_vertices[v2]; - - // delete old convex-hull - delete gE.m_convexHull; - // create the edge's convex-hull - ICHull * ch = new ICHull; - gE.m_convexHull = ch; - (*ch) = (*gV1.m_convexHull); - - // update distPoints - gE.m_distPoints = gV1.m_distPoints; - std::map::iterator itDP(gV2.m_distPoints.begin()); - std::map::iterator itDPEnd(gV2.m_distPoints.end()); - std::map::iterator itDP1; - - for(; itDP != itDPEnd; ++itDP) - { - itDP1 = gE.m_distPoints.find(itDP->first); - if (itDP1 == gE.m_distPoints.end()) - { - gE.m_distPoints[itDP->first].m_distOnly = (itDP->second).m_distOnly; - if ( !(itDP->second).m_distOnly ) - { - ch->AddPoint(m_points[itDP->first], itDP->first); - } - } - else - { - if ( (itDP1->second).m_distOnly && !(itDP->second).m_distOnly) - { - gE.m_distPoints[itDP->first].m_distOnly = false; - ch->AddPoint(m_points[itDP->first], itDP->first); - } - } - } - - ch->SetDistPoints(&gE.m_distPoints); - // create the convex-hull - while (ch->Process() == ICHullErrorInconsistent) // if we face problems when constructing the visual-hull. really ugly!!!! - { -// if (m_callBack) (*m_callBack)("\t Problem with convex-hull construction [HACD::ComputeEdgeCost]\n", 0.0, 0.0, 0); - ch = new ICHull; - CircularList & verticesCH = (gE.m_convexHull)->GetMesh().m_vertices; - size_t nV = verticesCH.GetSize(); - long ptIndex = 0; - verticesCH.Next(); - for(size_t v = 1; v < nV; ++v) - { - ptIndex = verticesCH.GetHead()->GetData().m_name; - if (ptIndex != ICHull::sc_dummyIndex/* && ptIndex < m_nPoints*/) - ch->AddPoint(m_points[ptIndex], ptIndex); - verticesCH.Next(); - } - delete gE.m_convexHull; - gE.m_convexHull = ch; - } - double volume = 0.0; - double concavity = 0.0; - if (ch->IsFlat()) - { - bool insideHull; - std::map::iterator itDP(gE.m_distPoints.begin()); - std::map::iterator itDPEnd(gE.m_distPoints.end()); - for(; itDP != itDPEnd; ++itDP) - { - if (itDP->first >= 0) - { - concavity = std::max(concavity, ch->ComputeDistance(itDP->first, m_points[itDP->first], m_normals[itDP->first], insideHull, false)); - } - } - } - else - { - if (m_addNeighboursDistPoints) - { // add distance points from adjacent clusters - std::set eEdges; - std::set_union(gV1.m_edges.begin(), - gV1.m_edges.end(), - gV2.m_edges.begin(), - gV2.m_edges.end(), - std::inserter( eEdges, eEdges.begin() ) ); - - std::set::const_iterator ed(eEdges.begin()); - std::set::const_iterator itEnd(eEdges.end()); - long a, b, c; - for(; ed != itEnd; ++ed) - { - a = m_graph.m_edges[*ed].m_v1; - b = m_graph.m_edges[*ed].m_v2; - if ( a != v2 && a != v1) - { - c = a; - } - else if ( b != v2 && b != v1) - { - c = b; - } - else - { - c = -1; - } - if ( c > 0) - { - GraphVertex & gVC = m_graph.m_vertices[c]; - std::map::iterator itDP(gVC.m_distPoints.begin()); - std::map::iterator itDPEnd(gVC.m_distPoints.end()); - std::map::iterator itDP1; - for(; itDP != itDPEnd; ++itDP) - { - itDP1 = gE.m_distPoints.find(itDP->first); - if (itDP1 == gE.m_distPoints.end()) - { - if (itDP->first >= 0 && itDP1 == gE.m_distPoints.end() && ch->IsInside(m_points[itDP->first])) - { - gE.m_distPoints[itDP->first].m_distOnly = true; - } - else if (itDP->first < 0 && ch->IsInside(m_facePoints[-itDP->first-1])) - { - gE.m_distPoints[itDP->first].m_distOnly = true; - } - } - } - } - } - } - concavity = Concavity(*ch, gE.m_distPoints); - } - - // compute boudary edges - double perimeter = 0.0; - double surf = 1.0; - if (m_alpha > 0.0) - { - gE.m_boudaryEdges.clear(); - std::set_symmetric_difference (gV1.m_boudaryEdges.begin(), - gV1.m_boudaryEdges.end(), - gV2.m_boudaryEdges.begin(), - gV2.m_boudaryEdges.end(), - std::inserter( gE.m_boudaryEdges, - gE.m_boudaryEdges.begin() ) ); - - std::set::const_iterator itBE(gE.m_boudaryEdges.begin()); - std::set::const_iterator itBEEnd(gE.m_boudaryEdges.end()); - for(; itBE != itBEEnd; ++itBE) - { - perimeter += (m_points[static_cast((*itBE) >> 32)] - - m_points[static_cast((*itBE) & 0xFFFFFFFFULL)]).GetNorm(); - } - surf = gV1.m_surf + gV2.m_surf; - } - double ratio = perimeter * perimeter / (4.0 * sc_pi * surf); - gE.m_volume = (m_beta == 0.0)?0.0:ch->ComputeVolume()/pow(m_scale, 3.0); // cluster's volume - gE.m_surf = surf; // cluster's area - gE.m_perimeter = perimeter; // cluster's perimeter - gE.m_concavity = concavity; // cluster's concavity - gE.m_error = static_cast(concavity + m_alpha * ratio + m_beta * volume); // cluster's priority - } - bool HACD::InitializePriorityQueue() - { - m_pqueue.reserve(m_graph.m_nE + 100); - for (size_t e=0; e < m_graph.m_nE; ++e) - { - ComputeEdgeCost(static_cast(e)); - m_pqueue.push(GraphEdgePriorityQueue(static_cast(e), m_graph.m_edges[e].m_error)); - } - return true; - } - void HACD::Simplify() - { - long v1 = -1; - long v2 = -1; - double progressOld = -1.0; - double progress = 0.0; - double globalConcavity = 0.0; - char msg[1024]; - double ptgStep = 1.0; - while ( (globalConcavity < m_concavity) && - (m_graph.GetNVertices() > m_nMinClusters) && - (m_graph.GetNEdges() > 0)) - { - progress = 100.0-m_graph.GetNVertices() * 100.0 / m_nTriangles; - if (fabs(progress-progressOld) > ptgStep && m_callBack) - { - sprintf(msg, "%3.2f %% V = %lu \t C = %f \t \t \r", progress, static_cast(m_graph.GetNVertices()), globalConcavity); - (*m_callBack)(msg, progress, globalConcavity, m_graph.GetNVertices()); - progressOld = progress; - if (progress > 99.0) - { - ptgStep = 0.01; - } - else if (progress > 90.0) - { - ptgStep = 0.1; - } - } - - GraphEdgePriorityQueue currentEdge(0,0.0); - bool done = false; - do - { - done = false; - if (m_pqueue.size() == 0) - { - done = true; - break; - } - currentEdge = m_pqueue.top(); - m_pqueue.pop(); - } - while ( m_graph.m_edges[currentEdge.m_name].m_deleted || - m_graph.m_edges[currentEdge.m_name].m_error != currentEdge.m_priority); - - - if (m_graph.m_edges[currentEdge.m_name].m_concavity < m_concavity && !done) - { - globalConcavity = std::max(globalConcavity ,m_graph.m_edges[currentEdge.m_name].m_concavity); - v1 = m_graph.m_edges[currentEdge.m_name].m_v1; - v2 = m_graph.m_edges[currentEdge.m_name].m_v2; - // update vertex info - m_graph.m_vertices[v1].m_error = m_graph.m_edges[currentEdge.m_name].m_error; - m_graph.m_vertices[v1].m_surf = m_graph.m_edges[currentEdge.m_name].m_surf; - m_graph.m_vertices[v1].m_volume = m_graph.m_edges[currentEdge.m_name].m_volume; - m_graph.m_vertices[v1].m_concavity = m_graph.m_edges[currentEdge.m_name].m_concavity; - m_graph.m_vertices[v1].m_perimeter = m_graph.m_edges[currentEdge.m_name].m_perimeter; - m_graph.m_vertices[v1].m_distPoints = m_graph.m_edges[currentEdge.m_name].m_distPoints; - (*m_graph.m_vertices[v1].m_convexHull) = (*m_graph.m_edges[currentEdge.m_name].m_convexHull); - (m_graph.m_vertices[v1].m_convexHull)->SetDistPoints(&(m_graph.m_vertices[v1].m_distPoints)); - m_graph.m_vertices[v1].m_boudaryEdges = m_graph.m_edges[currentEdge.m_name].m_boudaryEdges; - - // We apply the optimal ecol -// std::cout << "v1 " << v1 << " v2 " << v2 << std::endl; - m_graph.EdgeCollapse(v1, v2); - // recompute the adjacent edges costs - std::set::const_iterator itE(m_graph.m_vertices[v1].m_edges.begin()), - itEEnd(m_graph.m_vertices[v1].m_edges.end()); - for(; itE != itEEnd; ++itE) - { - size_t e = *itE; - ComputeEdgeCost(static_cast(e)); - m_pqueue.push(GraphEdgePriorityQueue(static_cast(e), m_graph.m_edges[e].m_error)); - } - } - else - { - break; - } - } - while (!m_pqueue.empty()) - { - m_pqueue.pop(); - } - - m_cVertices.clear(); - m_nClusters = m_graph.GetNVertices(); - m_cVertices.reserve(m_nClusters); - for (size_t p=0, v = 0; v != m_graph.m_vertices.size(); ++v) - { - if (!m_graph.m_vertices[v].m_deleted) - { - if (m_callBack) - { - char msg[1024]; - sprintf(msg, "\t CH \t %lu \t %lf \t %lf\n", static_cast(p), m_graph.m_vertices[v].m_concavity, m_graph.m_vertices[v].m_error); - (*m_callBack)(msg, 0.0, 0.0, m_nClusters); - p++; - } - m_cVertices.push_back(static_cast(v)); - } - } - if (m_callBack) - { - sprintf(msg, "# clusters = %lu \t C = %f\n", static_cast(m_nClusters), globalConcavity); - (*m_callBack)(msg, progress, globalConcavity, m_graph.GetNVertices()); - } - - } - - bool HACD::Compute(bool fullCH, bool exportDistPoints) - { - gCancelRequest = false; - - if ( !m_points || !m_triangles || !m_nPoints || !m_nTriangles) - { - return false; - } - size_t nV = m_nTriangles; - if (m_callBack) - { - std::ostringstream msg; - msg << "+ Mesh" << std::endl; - msg << "\t # vertices \t" << m_nPoints << std::endl; - msg << "\t # triangles \t" << m_nTriangles << std::endl; - msg << "+ Parameters" << std::endl; - msg << "\t min # of clusters \t" << m_nMinClusters << std::endl; - msg << "\t max concavity \t" << m_concavity << std::endl; - msg << "\t compacity weigth \t" << m_alpha << std::endl; - msg << "\t volume weigth \t" << m_beta << std::endl; - msg << "\t # vertices per convex-hull \t" << m_nVerticesPerCH << std::endl; - msg << "\t scale \t" << m_scale << std::endl; - msg << "\t add extra distance points \t" << m_addExtraDistPoints << std::endl; - msg << "\t add neighbours distance points \t" << m_addNeighboursDistPoints << std::endl; - msg << "\t add face distance points \t" << m_addFacesPoints << std::endl; - msg << "\t produce full convex-hulls \t" << fullCH << std::endl; - msg << "\t max. distance to connect CCs \t" << m_ccConnectDist << std::endl; - (*m_callBack)(msg.str().c_str(), 0.0, 0.0, nV); - } - if (m_callBack) (*m_callBack)("+ Normalizing Data\n", 0.0, 0.0, nV); - NormalizeData(); - if (m_callBack) (*m_callBack)("+ Creating Graph\n", 0.0, 0.0, nV); - CreateGraph(); - // Compute the surfaces and perimeters of all the faces - if (m_callBack) (*m_callBack)("+ Initializing Dual Graph\n", 0.0, 0.0, nV); - if (gCancelRequest) - return false; - - InitializeDualGraph(); - if (m_callBack) (*m_callBack)("+ Initializing Priority Queue\n", 0.0, 0.0, nV); - if (gCancelRequest) - return false; - - InitializePriorityQueue(); - // we simplify the graph - if (m_callBack) (*m_callBack)("+ Simplification ...\n", 0.0, 0.0, m_nTriangles); - Simplify(); - if (m_callBack) (*m_callBack)("+ Denormalizing Data\n", 0.0, 0.0, m_nClusters); - DenormalizeData(); - if (m_callBack) (*m_callBack)("+ Computing final convex-hulls\n", 0.0, 0.0, m_nClusters); - delete [] m_convexHulls; - m_convexHulls = new ICHull[m_nClusters]; - delete [] m_partition; - m_partition = new long [m_nTriangles]; - for (size_t p = 0; p != m_cVertices.size(); ++p) - { - size_t v = m_cVertices[p]; - m_partition[v] = static_cast(p); - for(size_t a = 0; a < m_graph.m_vertices[v].m_ancestors.size(); a++) - { - m_partition[m_graph.m_vertices[v].m_ancestors[a]] = static_cast(p); - } - // compute the convex-hull - const std::map & pointsCH = m_graph.m_vertices[v].m_distPoints; - std::map::const_iterator itCH(pointsCH.begin()); - std::map::const_iterator itCHEnd(pointsCH.end()); - for(; itCH != itCHEnd; ++itCH) - { - if (!(itCH->second).m_distOnly) - { - m_convexHulls[p].AddPoint(m_points[itCH->first], itCH->first); - } - } - m_convexHulls[p].SetDistPoints(&m_graph.m_vertices[v].m_distPoints); - if (fullCH) - { - m_convexHulls[p].Process(); - } - else - { - m_convexHulls[p].Process(static_cast(m_nVerticesPerCH)); - } - if (exportDistPoints) - { - itCH = pointsCH.begin(); - for(; itCH != itCHEnd; ++itCH) - { - if ((itCH->second).m_distOnly) - { - if (itCH->first >= 0) - { - m_convexHulls[p].AddPoint(m_points[itCH->first], itCH->first); - } - else - { - m_convexHulls[p].AddPoint(m_facePoints[-itCH->first-1], itCH->first); - } - } - } - } - } - return true; - } - - size_t HACD::GetNTrianglesCH(size_t numCH) const - { - if (numCH >= m_nClusters) - { - return 0; - } - return m_convexHulls[numCH].GetMesh().GetNTriangles(); - } - size_t HACD::GetNPointsCH(size_t numCH) const - { - if (numCH >= m_nClusters) - { - return 0; - } - return m_convexHulls[numCH].GetMesh().GetNVertices(); - } - - bool HACD::GetCH(size_t numCH, Vec3 * const points, Vec3 * const triangles) - { - if (numCH >= m_nClusters) - { - return false; - } - m_convexHulls[numCH].GetMesh().GetIFS(points, triangles); - return true; - } - - bool HACD::Save(const char * fileName, bool uniColor, long numCluster) const - { - std::ofstream fout(fileName); - if (fout.is_open()) - { - if (m_callBack) - { - char msg[1024]; - sprintf(msg, "Saving %s\n", fileName); - (*m_callBack)(msg, 0.0, 0.0, m_graph.GetNVertices()); - } - Material mat; - if (numCluster < 0) - { - for (size_t p = 0; p != m_nClusters; ++p) - { - if (!uniColor) - { - mat.m_diffuseColor.X() = mat.m_diffuseColor.Y() = mat.m_diffuseColor.Z() = 0.0; - while (mat.m_diffuseColor.X() == mat.m_diffuseColor.Y() || - mat.m_diffuseColor.Z() == mat.m_diffuseColor.Y() || - mat.m_diffuseColor.Z() == mat.m_diffuseColor.X() ) - { - mat.m_diffuseColor.X() = (rand()%100) / 100.0; - mat.m_diffuseColor.Y() = (rand()%100) / 100.0; - mat.m_diffuseColor.Z() = (rand()%100) / 100.0; - } - } - m_convexHulls[p].GetMesh().SaveVRML2(fout, mat); - } - } - else if (numCluster < static_cast(m_cVertices.size())) - { - m_convexHulls[numCluster].GetMesh().SaveVRML2(fout, mat); - } - fout.close(); - return true; - } - else - { - if (m_callBack) - { - char msg[1024]; - sprintf(msg, "Error saving %s\n", fileName); - (*m_callBack)(msg, 0.0, 0.0, m_graph.GetNVertices()); - } - return false; - } - } -} - - diff --git a/extern/bullet/src/Extras/HACD/hacdHACD.h b/extern/bullet/src/Extras/HACD/hacdHACD.h deleted file mode 100644 index 0b2415ba6965..000000000000 --- a/extern/bullet/src/Extras/HACD/hacdHACD.h +++ /dev/null @@ -1,282 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) - All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#pragma once -#ifndef HACD_HACD_H -#define HACD_HACD_H -#include "hacdVersion.h" -#include "hacdVector.h" -#include "hacdGraph.h" -#include "hacdICHull.h" -#include -#include -#include -#include - -namespace HACD -{ - const double sc_pi = 3.14159265; - class HACD; - - // just to be able to set the capcity of the container - - template, class _Pr = std::less > - class reservable_priority_queue: public std::priority_queue<_Ty, _Container, _Pr> - { - typedef typename std::priority_queue<_Ty, _Container, _Pr>::size_type size_type; - public: - reservable_priority_queue(size_type capacity = 0) { reserve(capacity); }; - void reserve(size_type capacity) { this->c.reserve(capacity); } - size_type capacity() const { return this->c.capacity(); } - }; - - //! priority queque element - class GraphEdgePriorityQueue - { - public: - //! Constructor - //! @param name edge's id - //! @param priority edge's priority - GraphEdgePriorityQueue(long name, Real priority) - { - m_name = name; - m_priority = priority; - } - //! Destructor - ~GraphEdgePriorityQueue(void){} - private: - long m_name; //!< edge name - Real m_priority; //!< priority - //! Operator < for GraphEdgePQ - friend bool operator<(const GraphEdgePriorityQueue & lhs, const GraphEdgePriorityQueue & rhs); - //! Operator > for GraphEdgePQ - friend bool operator>(const GraphEdgePriorityQueue & lhs, const GraphEdgePriorityQueue & rhs); - friend class HACD; - }; - inline bool operator<(const GraphEdgePriorityQueue & lhs, const GraphEdgePriorityQueue & rhs) - { - return lhs.m_priority(const GraphEdgePriorityQueue & lhs, const GraphEdgePriorityQueue & rhs) - { - return lhs.m_priority>rhs.m_priority; - } - typedef bool (*CallBackFunction)(const char *, double, double, size_t); - - //! Provides an implementation of the Hierarchical Approximate Convex Decomposition (HACD) technique described in "A Simple and Efficient Approach for 3D Mesh Approximate Convex Decomposition" Game Programming Gems 8 - Chapter 2.8, p.202. A short version of the chapter was published in ICIP09 and is available at ftp://ftp.elet.polimi.it/users/Stefano.Tubaro/ICIP_USB_Proceedings_v2/pdfs/0003501.pdf - class HACD - { - public: - - //! Gives the triangles partitionas an array of size m_nTriangles where the i-th element specifies the cluster to which belong the i-th triangle - //! @return triangles partition - const long * GetPartition() const { return m_partition;} - //! Sets the scale factor - //! @param scale scale factor - void SetScaleFactor(double scale) { m_scale = scale;} - //! Gives the scale factor - //! @return scale factor - double GetScaleFactor() const { return m_scale;} - //! Sets the call-back function - //! @param callBack pointer to the call-back function - void SetCallBack(CallBackFunction callBack) { m_callBack = callBack;} - //! Gives the call-back function - //! @return pointer to the call-back function - CallBackFunction GetCallBack() const { return m_callBack;} - - //! Specifies whether faces points should be added when computing the concavity - //! @param addFacesPoints true = faces points should be added - void SetAddFacesPoints(bool addFacesPoints) { m_addFacesPoints = addFacesPoints;} - //! Specifies wheter faces points should be added when computing the concavity - //! @return true = faces points should be added - bool GetAddFacesPoints() const { return m_addFacesPoints;} - //! Specifies whether extra points should be added when computing the concavity - //! @param addExteraDistPoints true = extra points should be added - void SetAddExtraDistPoints(bool addExtraDistPoints) { m_addExtraDistPoints = addExtraDistPoints;} - //! Specifies wheter extra points should be added when computing the concavity - //! @return true = extra points should be added - bool GetAddExtraDistPoints() const { return m_addExtraDistPoints;} - //! Specifies whether extra points should be added when computing the concavity - //! @param addExteraDistPoints true = extra points should be added - void SetAddNeighboursDistPoints(bool addNeighboursDistPoints) { m_addNeighboursDistPoints = addNeighboursDistPoints;} - //! Specifies wheter extra points should be added when computing the concavity - //! @return true = extra points should be added - bool GetAddNeighboursDistPoints() const { return m_addNeighboursDistPoints;} - //! Sets the points of the input mesh (Remark: the input points will be scaled and shifted. Use DenormalizeData() to invert those operations) - //! @param points pointer to the input points - void SetPoints(Vec3 * points) { m_points = points;} - //! Gives the points of the input mesh (Remark: the input points will be scaled and shifted. Use DenormalizeData() to invert those operations) - //! @return pointer to the input points - const Vec3 * GetPoints() const { return m_points;} - //! Sets the triangles of the input mesh. - //! @param triangles points pointer to the input points - void SetTriangles(Vec3 * triangles) { m_triangles = triangles;} - //! Gives the triangles in the input mesh - //! @return pointer to the input triangles - const Vec3 * GetTriangles() const { return m_triangles;} - //! Sets the number of points in the input mesh. - //! @param nPoints number of points the input mesh - void SetNPoints(size_t nPoints) { m_nPoints = nPoints;} - //! Gives the number of points in the input mesh. - //! @return number of points the input mesh - size_t GetNPoints() const { return m_nPoints;} - //! Sets the number of triangles in the input mesh. - //! @param nTriangles number of triangles in the input mesh - void SetNTriangles(size_t nTriangles) { m_nTriangles = nTriangles;} - //! Gives the number of triangles in the input mesh. - //! @return number of triangles the input mesh - size_t GetNTriangles() const { return m_nTriangles;} - //! Sets the minimum number of clusters to be generated. - //! @param nClusters minimum number of clusters - void SetNClusters(size_t nClusters) { m_nMinClusters = nClusters;} - //! Gives the number of generated clusters. - //! @return number of generated clusters - size_t GetNClusters() const { return m_nClusters;} - //! Sets the maximum allowed concavity. - //! @param concavity maximum concavity - void SetConcavity(double concavity) { m_concavity = concavity;} - //! Gives the maximum allowed concavity. - //! @return maximum concavity - double GetConcavity() const { return m_concavity;} - //! Sets the maximum allowed distance to get CCs connected. - //! @param concavity maximum distance to get CCs connected - void SetConnectDist(double ccConnectDist) { m_ccConnectDist = ccConnectDist;} - //! Gives the maximum allowed distance to get CCs connected. - //! @return maximum distance to get CCs connected - double GetConnectDist() const { return m_ccConnectDist;} - //! Sets the volume weight. - //! @param beta volume weight - void SetVolumeWeight(double beta) { m_beta = beta;} - //! Gives the volume weight. - //! @return volume weight - double GetVolumeWeight() const { return m_beta;} - //! Sets the compacity weight (i.e. parameter alpha in ftp://ftp.elet.polimi.it/users/Stefano.Tubaro/ICIP_USB_Proceedings_v2/pdfs/0003501.pdf). - //! @param alpha compacity weight - void SetCompacityWeight(double alpha) { m_alpha = alpha;} - //! Gives the compacity weight (i.e. parameter alpha in ftp://ftp.elet.polimi.it/users/Stefano.Tubaro/ICIP_USB_Proceedings_v2/pdfs/0003501.pdf). - //! @return compacity weight - double GetCompacityWeight() const { return m_alpha;} - //! Sets the maximum number of vertices for each generated convex-hull. - //! @param nVerticesPerCH maximum # vertices per CH - void SetNVerticesPerCH(size_t nVerticesPerCH) { m_nVerticesPerCH = nVerticesPerCH;} - //! Gives the maximum number of vertices for each generated convex-hull. - //! @return maximum # vertices per CH - size_t GetNVerticesPerCH() const { return m_nVerticesPerCH;} - //! Gives the number of vertices for the cluster number numCH. - //! @return number of vertices - size_t GetNPointsCH(size_t numCH) const; - //! Gives the number of triangles for the cluster number numCH. - //! @param numCH cluster's number - //! @return number of triangles - size_t GetNTrianglesCH(size_t numCH) const; - //! Gives the vertices and the triangles of the cluster number numCH. - //! @param numCH cluster's number - //! @param points pointer to the vector of points to be filled - //! @param triangles pointer to the vector of triangles to be filled - //! @return true if sucess - bool GetCH(size_t numCH, Vec3 * const points, Vec3 * const triangles); - //! Computes the HACD decomposition. - //! @param fullCH specifies whether to generate convex-hulls with a full or limited (i.e. < m_nVerticesPerCH) number of vertices - //! @param exportDistPoints specifies wheter distance points should ne exported or not (used only for debugging). - //! @return true if sucess - bool Compute(bool fullCH=false, bool exportDistPoints=false); - //! Saves the generated convex-hulls in a VRML 2.0 file. - //! @param fileName the output file name - //! @param uniColor specifies whether the different convex-hulls should have the same color or not - //! @param numCluster specifies the cluster to be saved, if numCluster < 0 export all clusters - //! @return true if sucess - bool Save(const char * fileName, bool uniColor, long numCluster=-1) const; - //! Shifts and scales to the data to have all the coordinates between 0.0 and 1000.0. - void NormalizeData(); - //! Inverse the operations applied by NormalizeData(). - void DenormalizeData(); - //! Constructor. - HACD(void); - //! Destructor. - ~HACD(void); - - private: - //! Gives the edge index. - //! @param a first vertex id - //! @param b second vertex id - //! @return edge's index - static unsigned long long GetEdgeIndex(unsigned long long a, unsigned long long b) - { - if (a > b) return (a << 32) + b; - else return (b << 32) + a; - } - //! Computes the concavity of a cluster. - //! @param ch the cluster's convex-hull - //! @param distPoints the cluster's points - //! @return cluster's concavity - double Concavity(ICHull & ch, std::map & distPoints); - //! Computes the perimeter of a cluster. - //! @param triIndices the cluster's triangles - //! @param distPoints the cluster's points - //! @return cluster's perimeter - double ComputePerimeter(const std::vector & triIndices) const; - //! Creates the Graph by associating to each mesh triangle a vertex in the graph and to each couple of adjacent triangles an edge in the graph. - void CreateGraph(); - //! Initializes the graph costs and computes the vertices normals - void InitializeDualGraph(); - //! Computes the cost of an edge - //! @param e edge's id - void ComputeEdgeCost(size_t e); - //! Initializes the priority queue - //! @param fast specifies whether fast mode is used - //! @return true if success - bool InitializePriorityQueue(); - //! Cleans the intersection between convex-hulls - void CleanClusters(); - //! Computes convex-hulls from partition information - //! @param fullCH specifies whether to generate convex-hulls with a full or limited (i.e. < m_nVerticesPerCH) number of vertices - void ComputeConvexHulls(bool fullCH); - //! Simplifies the graph - //! @param fast specifies whether fast mode is used - void Simplify(); - - private: - double m_scale; //>! scale factor used for NormalizeData() and DenormalizeData() - Vec3 * m_triangles; //>! pointer the triangles array - Vec3 * m_points; //>! pointer the points array - Vec3 * m_facePoints; //>! pointer to the faces points array - Vec3 * m_faceNormals; //>! pointer to the faces normals array - Vec3 * m_normals; //>! pointer the normals array - size_t m_nTriangles; //>! number of triangles in the original mesh - size_t m_nPoints; //>! number of vertices in the original mesh - size_t m_nClusters; //>! number of clusters - size_t m_nMinClusters; //>! minimum number of clusters - double m_ccConnectDist; //>! maximum allowed distance to connect CCs - double m_concavity; //>! maximum concavity - double m_alpha; //>! compacity weigth - double m_beta; //>! volume weigth - double m_diag; //>! length of the BB diagonal - Vec3 m_barycenter; //>! barycenter of the mesh - std::vector< long > m_cVertices; //>! array of vertices each belonging to a different cluster - ICHull * m_convexHulls; //>! convex-hulls associated with the final HACD clusters - Graph m_graph; //>! simplification graph - size_t m_nVerticesPerCH; //>! maximum number of vertices per convex-hull - reservable_priority_queue, - std::greater::value_type> > m_pqueue; //!> priority queue - HACD(const HACD & rhs); - CallBackFunction m_callBack; //>! call-back function - long * m_partition; //>! array of size m_nTriangles where the i-th element specifies the cluster to which belong the i-th triangle - bool m_addFacesPoints; //>! specifies whether to add faces points or not - bool m_addExtraDistPoints; //>! specifies whether to add extra points for concave shapes or not - bool m_addNeighboursDistPoints; //>! specifies whether to add extra points from adjacent clusters or not - - }; -} -#endif diff --git a/extern/bullet/src/Extras/HACD/hacdICHull.cpp b/extern/bullet/src/Extras/HACD/hacdICHull.cpp deleted file mode 100644 index de2c7da92442..000000000000 --- a/extern/bullet/src/Extras/HACD/hacdICHull.cpp +++ /dev/null @@ -1,1019 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) - All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#include "hacdICHull.h" -#include -#include - -namespace HACD -{ - const long ICHull::sc_dummyIndex = std::numeric_limits::max(); - ICHull::ICHull(void) - { - m_distPoints = 0; - m_isFlat = false; - m_dummyVertex = 0; - } - bool ICHull::AddPoints(const Vec3 * points, size_t nPoints) - { - if (!points) - { - return false; - } - CircularListElement * vertex = NULL; - for (size_t i = 0; i < nPoints; i++) - { - vertex = m_mesh.AddVertex(); - vertex->GetData().m_pos.X() = points[i].X(); - vertex->GetData().m_pos.Y() = points[i].Y(); - vertex->GetData().m_pos.Z() = points[i].Z(); - vertex->GetData().m_name = static_cast(i); - } - return true; - } - bool ICHull::AddPoints(std::vector< Vec3 > points) - { - CircularListElement * vertex = NULL; - for (size_t i = 0; i < points.size(); i++) - { - vertex = m_mesh.AddVertex(); - vertex->GetData().m_pos.X() = points[i].X(); - vertex->GetData().m_pos.Y() = points[i].Y(); - vertex->GetData().m_pos.Z() = points[i].Z(); - } - return true; - } - - bool ICHull::AddPoint(const Vec3 & point, long id) - { - if (AddPoints(&point, 1)) - { - m_mesh.m_vertices.GetData().m_name = id; - return true; - } - return false; - } - - ICHullError ICHull::Process() - { - unsigned long addedPoints = 0; - if (m_mesh.GetNVertices() < 3) - { - return ICHullErrorNotEnoughPoints; - } - if (m_mesh.GetNVertices() == 3) - { - m_isFlat = true; - CircularListElement * t1 = m_mesh.AddTriangle(); - CircularListElement * t2 = m_mesh.AddTriangle(); - CircularListElement * v0 = m_mesh.m_vertices.GetHead(); - CircularListElement * v1 = v0->GetNext(); - CircularListElement * v2 = v1->GetNext(); - // Compute the normal to the plane - Vec3 p0 = v0->GetData().m_pos; - Vec3 p1 = v1->GetData().m_pos; - Vec3 p2 = v2->GetData().m_pos; - m_normal = (p1-p0) ^ (p2-p0); - m_normal.Normalize(); - t1->GetData().m_vertices[0] = v0; - t1->GetData().m_vertices[1] = v1; - t1->GetData().m_vertices[2] = v2; - t2->GetData().m_vertices[0] = v1; - t2->GetData().m_vertices[1] = v2; - t2->GetData().m_vertices[2] = v2; - return ICHullErrorOK; - } - if (m_isFlat) - { - m_mesh.m_edges.Clear(); - m_mesh.m_triangles.Clear(); - m_isFlat = false; - } - if (m_mesh.GetNTriangles() == 0) // we have to create the first polyhedron - { - ICHullError res = DoubleTriangle(); - if (res != ICHullErrorOK) - { - return res; - } - else - { - addedPoints += 3; - } - } - CircularList & vertices = m_mesh.GetVertices(); - // go to the first added and not processed vertex - while (!(vertices.GetHead()->GetPrev()->GetData().m_tag)) - { - vertices.Prev(); - } - while (!vertices.GetData().m_tag) // not processed - { - vertices.GetData().m_tag = true; - if (ProcessPoint()) - { - addedPoints++; - CleanUp(addedPoints); - vertices.Next(); - if (!GetMesh().CheckConsistancy()) - { - return ICHullErrorInconsistent; - } - } - } - if (m_isFlat) - { - std::vector< CircularListElement * > trianglesToDuplicate; - size_t nT = m_mesh.GetNTriangles(); - for(size_t f = 0; f < nT; f++) - { - TMMTriangle & currentTriangle = m_mesh.m_triangles.GetHead()->GetData(); - if( currentTriangle.m_vertices[0]->GetData().m_name == sc_dummyIndex || - currentTriangle.m_vertices[1]->GetData().m_name == sc_dummyIndex || - currentTriangle.m_vertices[2]->GetData().m_name == sc_dummyIndex ) - { - m_trianglesToDelete.push_back(m_mesh.m_triangles.GetHead()); - for(int k = 0; k < 3; k++) - { - for(int h = 0; h < 2; h++) - { - if (currentTriangle.m_edges[k]->GetData().m_triangles[h] == m_mesh.m_triangles.GetHead()) - { - currentTriangle.m_edges[k]->GetData().m_triangles[h] = 0; - break; - } - } - } - } - else - { - trianglesToDuplicate.push_back(m_mesh.m_triangles.GetHead()); - } - m_mesh.m_triangles.Next(); - } - size_t nE = m_mesh.GetNEdges(); - for(size_t e = 0; e < nE; e++) - { - TMMEdge & currentEdge = m_mesh.m_edges.GetHead()->GetData(); - if( currentEdge.m_triangles[0] == 0 && currentEdge.m_triangles[1] == 0) - { - m_edgesToDelete.push_back(m_mesh.m_edges.GetHead()); - } - m_mesh.m_edges.Next(); - } - m_mesh.m_vertices.Delete(m_dummyVertex); - m_dummyVertex = 0; - size_t nV = m_mesh.GetNVertices(); - CircularList & vertices = m_mesh.GetVertices(); - for(size_t v = 0; v < nV; ++v) - { - vertices.GetData().m_tag = false; - vertices.Next(); - } - CleanEdges(); - CleanTriangles(); - CircularListElement * newTriangle; - for(size_t t = 0; t < trianglesToDuplicate.size(); t++) - { - newTriangle = m_mesh.AddTriangle(); - newTriangle->GetData().m_vertices[0] = trianglesToDuplicate[t]->GetData().m_vertices[1]; - newTriangle->GetData().m_vertices[1] = trianglesToDuplicate[t]->GetData().m_vertices[0]; - newTriangle->GetData().m_vertices[2] = trianglesToDuplicate[t]->GetData().m_vertices[2]; - } - } - return ICHullErrorOK; - } - ICHullError ICHull::Process(unsigned long nPointsCH) - { - unsigned long addedPoints = 0; - if (nPointsCH < 3 || m_mesh.GetNVertices() < 3) - { - return ICHullErrorNotEnoughPoints; - } - if (m_mesh.GetNVertices() == 3) - { - m_isFlat = true; - CircularListElement * t1 = m_mesh.AddTriangle(); - CircularListElement * t2 = m_mesh.AddTriangle(); - CircularListElement * v0 = m_mesh.m_vertices.GetHead(); - CircularListElement * v1 = v0->GetNext(); - CircularListElement * v2 = v1->GetNext(); - // Compute the normal to the plane - Vec3 p0 = v0->GetData().m_pos; - Vec3 p1 = v1->GetData().m_pos; - Vec3 p2 = v2->GetData().m_pos; - m_normal = (p1-p0) ^ (p2-p0); - m_normal.Normalize(); - t1->GetData().m_vertices[0] = v0; - t1->GetData().m_vertices[1] = v1; - t1->GetData().m_vertices[2] = v2; - t2->GetData().m_vertices[0] = v1; - t2->GetData().m_vertices[1] = v0; - t2->GetData().m_vertices[2] = v2; - return ICHullErrorOK; - } - - if (m_isFlat) - { - m_mesh.m_triangles.Clear(); - m_mesh.m_edges.Clear(); - m_isFlat = false; - } - - if (m_mesh.GetNTriangles() == 0) // we have to create the first polyhedron - { - ICHullError res = DoubleTriangle(); - if (res != ICHullErrorOK) - { - return res; - } - else - { - addedPoints += 3; - } - } - CircularList & vertices = m_mesh.GetVertices(); - while (!vertices.GetData().m_tag && addedPoints < nPointsCH) // not processed - { - if (!FindMaxVolumePoint()) - { - break; - } - vertices.GetData().m_tag = true; - if (ProcessPoint()) - { - addedPoints++; - CleanUp(addedPoints); - if (!GetMesh().CheckConsistancy()) - { - return ICHullErrorInconsistent; - } - vertices.Next(); - } - } - // delete remaining points - while (!vertices.GetData().m_tag) - { - if (vertices.GetHead() == m_dummyVertex) - m_dummyVertex = 0; - vertices.Delete(); - } - if (m_isFlat) - { - std::vector< CircularListElement * > trianglesToDuplicate; - size_t nT = m_mesh.GetNTriangles(); - for(size_t f = 0; f < nT; f++) - { - TMMTriangle & currentTriangle = m_mesh.m_triangles.GetHead()->GetData(); - if( currentTriangle.m_vertices[0]->GetData().m_name == sc_dummyIndex || - currentTriangle.m_vertices[1]->GetData().m_name == sc_dummyIndex || - currentTriangle.m_vertices[2]->GetData().m_name == sc_dummyIndex ) - { - m_trianglesToDelete.push_back(m_mesh.m_triangles.GetHead()); - for(int k = 0; k < 3; k++) - { - for(int h = 0; h < 2; h++) - { - if (currentTriangle.m_edges[k]->GetData().m_triangles[h] == m_mesh.m_triangles.GetHead()) - { - currentTriangle.m_edges[k]->GetData().m_triangles[h] = 0; - break; - } - } - } - } - else - { - trianglesToDuplicate.push_back(m_mesh.m_triangles.GetHead()); - } - m_mesh.m_triangles.Next(); - } - size_t nE = m_mesh.GetNEdges(); - for(size_t e = 0; e < nE; e++) - { - TMMEdge & currentEdge = m_mesh.m_edges.GetHead()->GetData(); - if( currentEdge.m_triangles[0] == 0 && currentEdge.m_triangles[1] == 0) - { - m_edgesToDelete.push_back(m_mesh.m_edges.GetHead()); - } - m_mesh.m_edges.Next(); - } - m_mesh.m_vertices.Delete(m_dummyVertex); - m_dummyVertex = 0; - size_t nV = m_mesh.GetNVertices(); - CircularList & vertices = m_mesh.GetVertices(); - for(size_t v = 0; v < nV; ++v) - { - vertices.GetData().m_tag = false; - vertices.Next(); - } - CleanEdges(); - CleanTriangles(); - CircularListElement * newTriangle; - for(size_t t = 0; t < trianglesToDuplicate.size(); t++) - { - newTriangle = m_mesh.AddTriangle(); - newTriangle->GetData().m_vertices[0] = trianglesToDuplicate[t]->GetData().m_vertices[1]; - newTriangle->GetData().m_vertices[1] = trianglesToDuplicate[t]->GetData().m_vertices[0]; - newTriangle->GetData().m_vertices[2] = trianglesToDuplicate[t]->GetData().m_vertices[2]; - } - } - return ICHullErrorOK; - } - bool ICHull::FindMaxVolumePoint() - { - CircularList & vertices = m_mesh.GetVertices(); - CircularListElement * vMaxVolume = 0; - CircularListElement * vHeadPrev = vertices.GetHead()->GetPrev(); - - double maxVolume = 0.0; - double volume = 0.0; - - while (!vertices.GetData().m_tag) // not processed - { - if (ComputePointVolume(volume, false)) - { - if ( maxVolume < volume) - { - maxVolume = volume; - vMaxVolume = vertices.GetHead(); - } - vertices.Next(); - } - } - CircularListElement * vHead = vHeadPrev->GetNext(); - vertices.GetHead() = vHead; - - if (!vMaxVolume) - { - return false; - } - - if (vMaxVolume != vHead) - { - Vec3 pos = vHead->GetData().m_pos; - long id = vHead->GetData().m_name; - vHead->GetData().m_pos = vMaxVolume->GetData().m_pos; - vHead->GetData().m_name = vMaxVolume->GetData().m_name; - vMaxVolume->GetData().m_pos = pos; - vHead->GetData().m_name = id; - } - - - return true; - } - ICHullError ICHull::DoubleTriangle() - { - // find three non colinear points - m_isFlat = false; - CircularList & vertices = m_mesh.GetVertices(); - CircularListElement * v0 = vertices.GetHead(); - while( Colinear(v0->GetData().m_pos, - v0->GetNext()->GetData().m_pos, - v0->GetNext()->GetNext()->GetData().m_pos)) - { - if ( (v0 = v0->GetNext()) == vertices.GetHead()) - { - return ICHullErrorCoplanarPoints; - } - } - CircularListElement * v1 = v0->GetNext(); - CircularListElement * v2 = v1->GetNext(); - // mark points as processed - v0->GetData().m_tag = v1->GetData().m_tag = v2->GetData().m_tag = true; - - // create two triangles - CircularListElement * f0 = MakeFace(v0, v1, v2, 0); - MakeFace(v2, v1, v0, f0); - - // find a fourth non-coplanar point to form tetrahedron - CircularListElement * v3 = v2->GetNext(); - vertices.GetHead() = v3; - - double vol = Volume(v0->GetData().m_pos, v1->GetData().m_pos, v2->GetData().m_pos, v3->GetData().m_pos); - while (vol == 0.0 && !v3->GetNext()->GetData().m_tag) - { - v3 = v3->GetNext(); - vol = Volume(v0->GetData().m_pos, v1->GetData().m_pos, v2->GetData().m_pos, v3->GetData().m_pos); - } - if (vol == 0.0) - { - // compute the barycenter - Vec3 bary(0.0,0.0,0.0); - CircularListElement * vBary = v0; - do - { - bary += vBary->GetData().m_pos; - } - while ( (vBary = vBary->GetNext()) != v0); - bary /= static_cast(vertices.GetSize()); - - // Compute the normal to the plane - Vec3 p0 = v0->GetData().m_pos; - Vec3 p1 = v1->GetData().m_pos; - Vec3 p2 = v2->GetData().m_pos; - m_normal = (p1-p0) ^ (p2-p0); - m_normal.Normalize(); - // add dummy vertex placed at (bary + normal) - vertices.GetHead() = v2; - Vec3 newPt = bary + m_normal; - AddPoint(newPt, sc_dummyIndex); - m_dummyVertex = vertices.GetHead(); - m_isFlat = true; - v3 = v2->GetNext(); - vol = Volume(v0->GetData().m_pos, v1->GetData().m_pos, v2->GetData().m_pos, v3->GetData().m_pos); - return ICHullErrorOK; - } - else if (v3 != vertices.GetHead()) - { - TMMVertex temp; - temp.m_name = v3->GetData().m_name; - temp.m_pos = v3->GetData().m_pos; - v3->GetData().m_name = vertices.GetHead()->GetData().m_name; - v3->GetData().m_pos = vertices.GetHead()->GetData().m_pos; - vertices.GetHead()->GetData().m_name = temp.m_name; - vertices.GetHead()->GetData().m_pos = temp.m_pos; - } - return ICHullErrorOK; - } - CircularListElement * ICHull::MakeFace(CircularListElement * v0, - CircularListElement * v1, - CircularListElement * v2, - CircularListElement * fold) - { - CircularListElement * e0; - CircularListElement * e1; - CircularListElement * e2; - long index = 0; - if (!fold) // if first face to be created - { - e0 = m_mesh.AddEdge(); // create the three edges - e1 = m_mesh.AddEdge(); - e2 = m_mesh.AddEdge(); - } - else // otherwise re-use existing edges (in reverse order) - { - e0 = fold->GetData().m_edges[2]; - e1 = fold->GetData().m_edges[1]; - e2 = fold->GetData().m_edges[0]; - index = 1; - } - e0->GetData().m_vertices[0] = v0; e0->GetData().m_vertices[1] = v1; - e1->GetData().m_vertices[0] = v1; e1->GetData().m_vertices[1] = v2; - e2->GetData().m_vertices[0] = v2; e2->GetData().m_vertices[1] = v0; - // create the new face - CircularListElement * f = m_mesh.AddTriangle(); - f->GetData().m_edges[0] = e0; f->GetData().m_edges[1] = e1; f->GetData().m_edges[2] = e2; - f->GetData().m_vertices[0] = v0; f->GetData().m_vertices[1] = v1; f->GetData().m_vertices[2] = v2; - // link edges to face f - e0->GetData().m_triangles[index] = e1->GetData().m_triangles[index] = e2->GetData().m_triangles[index] = f; - return f; - } - CircularListElement * ICHull::MakeConeFace(CircularListElement * e, CircularListElement * p) - { - // create two new edges if they don't already exist - CircularListElement * newEdges[2]; - for(int i = 0; i < 2; ++i) - { - if ( !( newEdges[i] = e->GetData().m_vertices[i]->GetData().m_duplicate ) ) - { // if the edge doesn't exits add it and mark the vertex as duplicated - newEdges[i] = m_mesh.AddEdge(); - newEdges[i]->GetData().m_vertices[0] = e->GetData().m_vertices[i]; - newEdges[i]->GetData().m_vertices[1] = p; - e->GetData().m_vertices[i]->GetData().m_duplicate = newEdges[i]; - } - } - // make the new face - CircularListElement * newFace = m_mesh.AddTriangle(); - newFace->GetData().m_edges[0] = e; - newFace->GetData().m_edges[1] = newEdges[0]; - newFace->GetData().m_edges[2] = newEdges[1]; - MakeCCW(newFace, e, p); - for(int i=0; i < 2; ++i) - { - for(int j=0; j < 2; ++j) - { - if ( ! newEdges[i]->GetData().m_triangles[j] ) - { - newEdges[i]->GetData().m_triangles[j] = newFace; - break; - } - } - } - return newFace; - } - bool ICHull::ComputePointVolume(double &totalVolume, bool markVisibleFaces) - { - // mark visible faces - CircularListElement * fHead = m_mesh.GetTriangles().GetHead(); - CircularListElement * f = fHead; - CircularList & vertices = m_mesh.GetVertices(); - CircularListElement * vertex0 = vertices.GetHead(); - bool visible = false; - Vec3 pos0 = Vec3(vertex0->GetData().m_pos.X(), - vertex0->GetData().m_pos.Y(), - vertex0->GetData().m_pos.Z()); - double vol = 0.0; - totalVolume = 0.0; - Vec3 ver0, ver1, ver2; - do - { - ver0.X() = f->GetData().m_vertices[0]->GetData().m_pos.X(); - ver0.Y() = f->GetData().m_vertices[0]->GetData().m_pos.Y(); - ver0.Z() = f->GetData().m_vertices[0]->GetData().m_pos.Z(); - ver1.X() = f->GetData().m_vertices[1]->GetData().m_pos.X(); - ver1.Y() = f->GetData().m_vertices[1]->GetData().m_pos.Y(); - ver1.Z() = f->GetData().m_vertices[1]->GetData().m_pos.Z(); - ver2.X() = f->GetData().m_vertices[2]->GetData().m_pos.X(); - ver2.Y() = f->GetData().m_vertices[2]->GetData().m_pos.Y(); - ver2.Z() = f->GetData().m_vertices[2]->GetData().m_pos.Z(); - vol = Volume(ver0, ver1, ver2, pos0); - if ( vol < 0.0 ) - { - vol = fabs(vol); - totalVolume += vol; - if (markVisibleFaces) - { - f->GetData().m_visible = true; - m_trianglesToDelete.push_back(f); - } - visible = true; - } - f = f->GetNext(); - } - while (f != fHead); - - if (m_trianglesToDelete.size() == m_mesh.m_triangles.GetSize()) - { - for(size_t i = 0; i < m_trianglesToDelete.size(); i++) - { - m_trianglesToDelete[i]->GetData().m_visible = false; - } - visible = false; - } - // if no faces visible from p then p is inside the hull - if (!visible && markVisibleFaces) - { - if (vertices.GetHead() == m_dummyVertex) - m_dummyVertex = 0; - vertices.Delete(); - m_trianglesToDelete.clear(); - return false; - } - return true; - } - bool ICHull::ProcessPoint() - { - double totalVolume = 0.0; - if (!ComputePointVolume(totalVolume, true)) - { - return false; - } - // Mark edges in interior of visible region for deletion. - // Create a new face based on each border edge - CircularListElement * v0 = m_mesh.GetVertices().GetHead(); - CircularListElement * eHead = m_mesh.GetEdges().GetHead(); - CircularListElement * e = eHead; - CircularListElement * tmp = 0; - long nvisible = 0; - m_edgesToDelete.clear(); - m_edgesToUpdate.clear(); - do - { - tmp = e->GetNext(); - nvisible = 0; - for(int k = 0; k < 2; k++) - { - if ( e->GetData().m_triangles[k]->GetData().m_visible ) - { - nvisible++; - } - } - if ( nvisible == 2) - { - m_edgesToDelete.push_back(e); - } - else if ( nvisible == 1) - { - e->GetData().m_newFace = MakeConeFace(e, v0); - m_edgesToUpdate.push_back(e); - } - e = tmp; - } - while (e != eHead); - return true; - } - bool ICHull::MakeCCW(CircularListElement * f, - CircularListElement * e, - CircularListElement * v) - { - // the visible face adjacent to e - CircularListElement * fv; - if (e->GetData().m_triangles[0]->GetData().m_visible) - { - fv = e->GetData().m_triangles[0]; - } - else - { - fv = e->GetData().m_triangles[1]; - } - - // set vertex[0] and vertex[1] to have the same orientation as the corresponding vertices of fv. - long i; // index of e->m_vertices[0] in fv - CircularListElement * v0 = e->GetData().m_vertices[0]; - CircularListElement * v1 = e->GetData().m_vertices[1]; - for(i = 0; fv->GetData().m_vertices[i] != v0; i++); - - if ( fv->GetData().m_vertices[(i+1) % 3] != e->GetData().m_vertices[1] ) - { - f->GetData().m_vertices[0] = v1; - f->GetData().m_vertices[1] = v0; - } - else - { - f->GetData().m_vertices[0] = v0; - f->GetData().m_vertices[1] = v1; - // swap edges - CircularListElement * tmp = f->GetData().m_edges[0]; - f->GetData().m_edges[0] = f->GetData().m_edges[1]; - f->GetData().m_edges[1] = tmp; - } - f->GetData().m_vertices[2] = v; - return true; - } - bool ICHull::CleanUp(unsigned long & addedPoints) - { - bool r0 = CleanEdges(); - bool r1 = CleanTriangles(); - bool r2 = CleanVertices(addedPoints); - return r0 && r1 && r2; - } - bool ICHull::CleanEdges() - { - // integrate the new faces into the data structure - CircularListElement * e; - const std::vector *>::iterator itEndUpdate = m_edgesToUpdate.end(); - for(std::vector *>::iterator it = m_edgesToUpdate.begin(); it != itEndUpdate; ++it) - { - e = *it; - if ( e->GetData().m_newFace ) - { - if ( e->GetData().m_triangles[0]->GetData().m_visible) - { - e->GetData().m_triangles[0] = e->GetData().m_newFace; - } - else - { - e->GetData().m_triangles[1] = e->GetData().m_newFace; - } - e->GetData().m_newFace = 0; - } - } - // delete edges maked for deletion - CircularList & edges = m_mesh.GetEdges(); - const std::vector *>::iterator itEndDelete = m_edgesToDelete.end(); - for(std::vector *>::iterator it = m_edgesToDelete.begin(); it != itEndDelete; ++it) - { - edges.Delete(*it); - } - m_edgesToDelete.clear(); - m_edgesToUpdate.clear(); - return true; - } - bool ICHull::CleanTriangles() - { - CircularList & triangles = m_mesh.GetTriangles(); - const std::vector *>::iterator itEndDelete = m_trianglesToDelete.end(); - for(std::vector *>::iterator it = m_trianglesToDelete.begin(); it != itEndDelete; ++it) - { - if (m_distPoints) - { - if (m_isFlat) - { - // to be updated - } - else - { - std::set::const_iterator itPEnd((*it)->GetData().m_incidentPoints.end()); - std::set::const_iterator itP((*it)->GetData().m_incidentPoints.begin()); - std::map::iterator itPoint; - for(; itP != itPEnd; ++itP) - { - itPoint = m_distPoints->find(*itP); - if (itPoint != m_distPoints->end()) - { - itPoint->second.m_computed = false; - } - } - } - } - triangles.Delete(*it); - } - m_trianglesToDelete.clear(); - return true; - } - bool ICHull::CleanVertices(unsigned long & addedPoints) - { - // mark all vertices incident to some undeleted edge as on the hull - CircularList & edges = m_mesh.GetEdges(); - CircularListElement * e = edges.GetHead(); - size_t nE = edges.GetSize(); - for(size_t i = 0; i < nE; i++) - { - e->GetData().m_vertices[0]->GetData().m_onHull = true; - e->GetData().m_vertices[1]->GetData().m_onHull = true; - e = e->GetNext(); - } - // delete all the vertices that have been processed but are not on the hull - CircularList & vertices = m_mesh.GetVertices(); - CircularListElement * vHead = vertices.GetHead(); - CircularListElement * v = vHead; - v = v->GetPrev(); - do - { - if (v->GetData().m_tag && !v->GetData().m_onHull) - { - CircularListElement * tmp = v->GetPrev(); - if (tmp == m_dummyVertex) - m_dummyVertex = 0; - vertices.Delete(v); - v = tmp; - addedPoints--; - } - else - { - v->GetData().m_duplicate = 0; - v->GetData().m_onHull = false; - v = v->GetPrev(); - } - } - while (v->GetData().m_tag && v != vHead); - return true; - } - void ICHull::Clear() - { - m_mesh.Clear(); - m_edgesToDelete = std::vector *>(); - m_edgesToUpdate = std::vector *>(); - m_trianglesToDelete= std::vector *>(); - m_isFlat = false; - } - const ICHull & ICHull::operator=(ICHull & rhs) - { - if (&rhs != this) - { - m_mesh.Copy(rhs.m_mesh); - m_edgesToDelete = rhs.m_edgesToDelete; - m_edgesToUpdate = rhs.m_edgesToUpdate; - m_trianglesToDelete = rhs.m_trianglesToDelete; - m_isFlat = rhs.m_isFlat; - } - return (*this); - } - double ICHull::ComputeVolume() - { - size_t nV = m_mesh.m_vertices.GetSize(); - if (nV == 0 || m_isFlat) - { - return 0.0; - } - Vec3 bary(0.0, 0.0, 0.0); - for(size_t v = 0; v < nV; v++) - { - bary.X() += m_mesh.m_vertices.GetHead()->GetData().m_pos.X(); - bary.Y() += m_mesh.m_vertices.GetHead()->GetData().m_pos.Y(); - bary.Z() += m_mesh.m_vertices.GetHead()->GetData().m_pos.Z(); - m_mesh.m_vertices.Next(); - } - bary /= static_cast(nV); - - size_t nT = m_mesh.m_triangles.GetSize(); - Vec3 ver0, ver1, ver2; - double totalVolume = 0.0; - for(size_t t = 0; t < nT; t++) - { - ver0.X() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[0]->GetData().m_pos.X(); - ver0.Y() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[0]->GetData().m_pos.Y(); - ver0.Z() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[0]->GetData().m_pos.Z(); - ver1.X() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[1]->GetData().m_pos.X(); - ver1.Y() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[1]->GetData().m_pos.Y(); - ver1.Z() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[1]->GetData().m_pos.Z(); - ver2.X() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[2]->GetData().m_pos.X(); - ver2.Y() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[2]->GetData().m_pos.Y(); - ver2.Z() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[2]->GetData().m_pos.Z(); - totalVolume += Volume(ver0, ver1, ver2, bary); - m_mesh.m_triangles.Next(); - } - return totalVolume; - } - bool ICHull::IsInside(const Vec3 & pt0) - { - const Vec3 pt(pt0.X(), pt0.Y(), pt0.Z()); - if (m_isFlat) - { - size_t nT = m_mesh.m_triangles.GetSize(); - Vec3 ver0, ver1, ver2, a, b, c; - double u,v; - for(size_t t = 0; t < nT; t++) - { - ver0.X() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[0]->GetData().m_pos.X(); - ver0.Y() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[0]->GetData().m_pos.Y(); - ver0.Z() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[0]->GetData().m_pos.Z(); - ver1.X() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[1]->GetData().m_pos.X(); - ver1.Y() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[1]->GetData().m_pos.Y(); - ver1.Z() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[1]->GetData().m_pos.Z(); - ver2.X() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[2]->GetData().m_pos.X(); - ver2.Y() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[2]->GetData().m_pos.Y(); - ver2.Z() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[2]->GetData().m_pos.Z(); - a = ver1 - ver0; - b = ver2 - ver0; - c = pt - ver0; - u = c * a; - v = c * b; - if ( u >= 0.0 && u <= 1.0 && v >= 0.0 && u+v <= 1.0) - { - return true; - } - m_mesh.m_triangles.Next(); - } - return false; - } - else - { - size_t nT = m_mesh.m_triangles.GetSize(); - Vec3 ver0, ver1, ver2; - for(size_t t = 0; t < nT; t++) - { - ver0.X() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[0]->GetData().m_pos.X(); - ver0.Y() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[0]->GetData().m_pos.Y(); - ver0.Z() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[0]->GetData().m_pos.Z(); - ver1.X() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[1]->GetData().m_pos.X(); - ver1.Y() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[1]->GetData().m_pos.Y(); - ver1.Z() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[1]->GetData().m_pos.Z(); - ver2.X() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[2]->GetData().m_pos.X(); - ver2.Y() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[2]->GetData().m_pos.Y(); - ver2.Z() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[2]->GetData().m_pos.Z(); - if (Volume(ver0, ver1, ver2, pt) < 0.0) - { - return false; - } - m_mesh.m_triangles.Next(); - } - return true; - } - } - double ICHull::ComputeDistance(long name, const Vec3 & pt, const Vec3 & normal, bool & insideHull, bool updateIncidentPoints) - { - Vec3 ptNormal(static_cast(normal.X()), - static_cast(normal.Y()), - static_cast(normal.Z())); - Vec3 p0( static_cast(pt.X()), - static_cast(pt.Y()), - static_cast(pt.Z())); - - if (m_isFlat) - { - double distance = 0.0; - Vec3 chNormal(static_cast(m_normal.X()), - static_cast(m_normal.Y()), - static_cast(m_normal.Z())); - ptNormal -= (ptNormal * chNormal) * chNormal; - if (ptNormal.GetNorm() > 0.0) - { - ptNormal.Normalize(); - long nameVE1; - long nameVE2; - Vec3 pa, pb, d0, d1, d2, d3; - Vec3 p1 = p0 + ptNormal; - Vec3 p2, p3; - double mua, mub, s; - const double EPS = 0.00000000001; - size_t nE = m_mesh.GetNEdges(); - for(size_t e = 0; e < nE; e++) - { - TMMEdge & currentEdge = m_mesh.m_edges.GetHead()->GetData(); - nameVE1 = currentEdge.m_vertices[0]->GetData().m_name; - nameVE2 = currentEdge.m_vertices[1]->GetData().m_name; - if (currentEdge.m_triangles[0] == 0 || currentEdge.m_triangles[1] == 0) - { - if ( nameVE1==name || nameVE2==name ) - { - return 0.0; - } - /* - if (debug) std::cout << "V" << name - << " E " << nameVE1 << " " << nameVE2 << std::endl; - */ - - p2.X() = currentEdge.m_vertices[0]->GetData().m_pos.X(); - p2.Y() = currentEdge.m_vertices[0]->GetData().m_pos.Y(); - p2.Z() = currentEdge.m_vertices[0]->GetData().m_pos.Z(); - p3.X() = currentEdge.m_vertices[1]->GetData().m_pos.X(); - p3.Y() = currentEdge.m_vertices[1]->GetData().m_pos.Y(); - p3.Z() = currentEdge.m_vertices[1]->GetData().m_pos.Z(); - d0 = p3 - p2; - if (d0.GetNorm() > 0.0) - { - if (IntersectLineLine(p0, p1, p2, p3, pa, pb, mua, mub)) - { - d1 = pa - p2; - d2 = pa - pb; - d3 = pa - p0; - mua = d1.GetNorm()/d0.GetNorm(); - mub = d1*d0; - s = d3*ptNormal; - if (d2.GetNorm() < EPS && mua <= 1.0 && mub>=0.0 && s>0.0) - { - distance = std::max(distance, d3.GetNorm()); - } - } - } - } - m_mesh.m_edges.Next(); - } - } - return distance; - } - else - { - Vec3 ptNormal(static_cast(normal.X()), - static_cast(normal.Y()), - static_cast(normal.Z())); - - Vec3 impact; - long nhit; - double dist; - double distance = 0.0; - size_t nT = m_mesh.GetNTriangles(); - insideHull = false; - CircularListElement * face = 0; - Vec3 ver0, ver1, ver2; - for(size_t f = 0; f < nT; f++) - { - TMMTriangle & currentTriangle = m_mesh.m_triangles.GetHead()->GetData(); - /* - if (debug) std::cout << "T " << currentTriangle.m_vertices[0]->GetData().m_name << " " - << currentTriangle.m_vertices[1]->GetData().m_name << " " - << currentTriangle.m_vertices[2]->GetData().m_name << std::endl; - */ - if (currentTriangle.m_vertices[0]->GetData().m_name == name || - currentTriangle.m_vertices[1]->GetData().m_name == name || - currentTriangle.m_vertices[2]->GetData().m_name == name) - { - nhit = 1; - dist = 0.0; - } - else - { - ver0.X() = currentTriangle.m_vertices[0]->GetData().m_pos.X(); - ver0.Y() = currentTriangle.m_vertices[0]->GetData().m_pos.Y(); - ver0.Z() = currentTriangle.m_vertices[0]->GetData().m_pos.Z(); - ver1.X() = currentTriangle.m_vertices[1]->GetData().m_pos.X(); - ver1.Y() = currentTriangle.m_vertices[1]->GetData().m_pos.Y(); - ver1.Z() = currentTriangle.m_vertices[1]->GetData().m_pos.Z(); - ver2.X() = currentTriangle.m_vertices[2]->GetData().m_pos.X(); - ver2.Y() = currentTriangle.m_vertices[2]->GetData().m_pos.Y(); - ver2.Z() = currentTriangle.m_vertices[2]->GetData().m_pos.Z(); - nhit = IntersectRayTriangle(p0, ptNormal, ver0, ver1, ver2, dist); - } - - if (nhit == 1 && distance <= dist) - { - distance = dist; - insideHull = true; - face = m_mesh.m_triangles.GetHead(); -/* - std::cout << name << " -> T " << currentTriangle.m_vertices[0]->GetData().m_name << " " - << currentTriangle.m_vertices[1]->GetData().m_name << " " - << currentTriangle.m_vertices[2]->GetData().m_name << " Dist " - << dist << " P " << currentTriangle.m_normal * normal << std::endl; -*/ - if (dist > 0.1) - { - break; - } - } - m_mesh.m_triangles.Next(); - } - if (updateIncidentPoints && face && m_distPoints) - { - (*m_distPoints)[name].m_dist = static_cast(distance); - face->GetData().m_incidentPoints.insert(name); - } - return distance; - } - } -} - - diff --git a/extern/bullet/src/Extras/HACD/hacdICHull.h b/extern/bullet/src/Extras/HACD/hacdICHull.h deleted file mode 100644 index 548f992bdb4e..000000000000 --- a/extern/bullet/src/Extras/HACD/hacdICHull.h +++ /dev/null @@ -1,120 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) - All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#pragma once -#ifndef HACD_ICHULL_H -#define HACD_ICHULL_H -#include "hacdVersion.h" -#include "hacdManifoldMesh.h" -#include "hacdVector.h" -#include -#include -namespace HACD -{ - class DPoint; - class HACD; - //! Incremental Convex Hull algorithm (cf. http://maven.smith.edu/~orourke/books/ftp.html ). - enum ICHullError - { - ICHullErrorOK = 0, - ICHullErrorCoplanarPoints, - ICHullErrorNoVolume, - ICHullErrorInconsistent, - ICHullErrorNotEnoughPoints - }; - class ICHull - { - public: - //! - bool IsFlat() { return m_isFlat;} - //! - std::map * GetDistPoints() const { return m_distPoints;} - //! - void SetDistPoints(std::map * distPoints) { m_distPoints = distPoints;} - //! Returns the computed mesh - TMMesh & GetMesh() { return m_mesh;} - //! Add one point to the convex-hull - bool AddPoint(const Vec3 & point) {return AddPoints(&point, 1);} - //! Add one point to the convex-hull - bool AddPoint(const Vec3 & point, long id); - //! Add points to the convex-hull - bool AddPoints(const Vec3 * points, size_t nPoints); - bool AddPoints(std::vector< Vec3 > points); - //! - ICHullError Process(); - //! - ICHullError Process(unsigned long nPointsCH); - //! - double ComputeVolume(); - //! - bool IsInside(const Vec3 & pt0); - //! - double ComputeDistance(long name, const Vec3 & pt, const Vec3 & normal, bool & insideHull, bool updateIncidentPoints); - //! - const ICHull & operator=(ICHull & rhs); - - //! Constructor - ICHull(void); - //! Destructor - virtual ~ICHull(void) {}; - - private: - //! DoubleTriangle builds the initial double triangle. It first finds 3 noncollinear points and makes two faces out of them, in opposite order. It then finds a fourth point that is not coplanar with that face. The vertices are stored in the face structure in counterclockwise order so that the volume between the face and the point is negative. Lastly, the 3 newfaces to the fourth point are constructed and the data structures are cleaned up. - ICHullError DoubleTriangle(); - //! MakeFace creates a new face structure from three vertices (in ccw order). It returns a pointer to the face. - CircularListElement * MakeFace(CircularListElement * v0, - CircularListElement * v1, - CircularListElement * v2, - CircularListElement * fold); - //! - CircularListElement * MakeConeFace(CircularListElement * e, CircularListElement * v); - //! - bool ProcessPoint(); - //! - bool ComputePointVolume(double &totalVolume, bool markVisibleFaces); - //! - bool FindMaxVolumePoint(); - //! - bool CleanEdges(); - //! - bool CleanVertices(unsigned long & addedPoints); - //! - bool CleanTriangles(); - //! - bool CleanUp(unsigned long & addedPoints); - //! - bool MakeCCW(CircularListElement * f, - CircularListElement * e, - CircularListElement * v); - void Clear(); - private: - static const long sc_dummyIndex; - static const double sc_distMin; - TMMesh m_mesh; - std::vector *> m_edgesToDelete; - std::vector *> m_edgesToUpdate; - std::vector *> m_trianglesToDelete; - std::map * m_distPoints; - CircularListElement * m_dummyVertex; - Vec3 m_normal; - bool m_isFlat; - - - ICHull(const ICHull & rhs); - - friend class HACD; - }; - -} -#endif diff --git a/extern/bullet/src/Extras/HACD/hacdManifoldMesh.cpp b/extern/bullet/src/Extras/HACD/hacdManifoldMesh.cpp deleted file mode 100644 index 22a3576e43ed..000000000000 --- a/extern/bullet/src/Extras/HACD/hacdManifoldMesh.cpp +++ /dev/null @@ -1,577 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) - All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#include "hacdManifoldMesh.h" -using namespace std; - - -namespace HACD -{ - Material::Material(void) - { - m_diffuseColor.X() = 0.5; - m_diffuseColor.Y() = 0.5; - m_diffuseColor.Z() = 0.5; - m_specularColor.X() = 0.5; - m_specularColor.Y() = 0.5; - m_specularColor.Z() = 0.5; - m_ambientIntensity = 0.4; - m_emissiveColor.X() = 0.0; - m_emissiveColor.Y() = 0.0; - m_emissiveColor.Z() = 0.0; - m_shininess = 0.4; - m_transparency = 0.0; - } - - TMMVertex::TMMVertex(void) - { - m_name = 0; - m_id = 0; - m_duplicate = 0; - m_onHull = false; - m_tag = false; - } - TMMVertex::~TMMVertex(void) - { - } - TMMEdge::TMMEdge(void) - { - m_id = 0; - m_triangles[0] = m_triangles[1] = m_newFace = 0; - m_vertices[0] = m_vertices[1] = 0; - } - TMMEdge::~TMMEdge(void) - { - } - TMMTriangle::TMMTriangle(void) - { - m_id = 0; - for(int i = 0; i < 3; i++) - { - m_edges[i] = 0; - m_vertices[0] = 0; - } - m_visible = false; - } - TMMTriangle::~TMMTriangle(void) - { - } - TMMesh::TMMesh(void) - { - m_barycenter = Vec3(0,0,0); - m_diag = 1; - } - TMMesh::~TMMesh(void) - { - } - - void TMMesh::Print() - { - size_t nV = m_vertices.GetSize(); - std::cout << "-----------------------------" << std::endl; - std::cout << "vertices (" << nV << ")" << std::endl; - for(size_t v = 0; v < nV; v++) - { - const TMMVertex & currentVertex = m_vertices.GetData(); - std::cout << currentVertex.m_id << ", " - << currentVertex.m_pos.X() << ", " - << currentVertex.m_pos.Y() << ", " - << currentVertex.m_pos.Z() << std::endl; - m_vertices.Next(); - } - - - size_t nE = m_edges.GetSize(); - std::cout << "edges (" << nE << ")" << std::endl; - for(size_t e = 0; e < nE; e++) - { - const TMMEdge & currentEdge = m_edges.GetData(); - const CircularListElement * v0 = currentEdge.m_vertices[0]; - const CircularListElement * v1 = currentEdge.m_vertices[1]; - const CircularListElement * f0 = currentEdge.m_triangles[0]; - const CircularListElement * f1 = currentEdge.m_triangles[1]; - - std::cout << "-> (" << v0->GetData().m_name << ", " << v1->GetData().m_name << ")" << std::endl; - std::cout << "-> F0 (" << f0->GetData().m_vertices[0]->GetData().m_name << ", " - << f0->GetData().m_vertices[1]->GetData().m_name << ", " - << f0->GetData().m_vertices[2]->GetData().m_name <<")" << std::endl; - std::cout << "-> F1 (" << f1->GetData().m_vertices[0]->GetData().m_name << ", " - << f1->GetData().m_vertices[1]->GetData().m_name << ", " - << f1->GetData().m_vertices[2]->GetData().m_name << ")" << std::endl; - m_edges.Next(); - } - size_t nT = m_triangles.GetSize(); - std::cout << "triangles (" << nT << ")" << std::endl; - for(size_t t = 0; t < nT; t++) - { - const TMMTriangle & currentTriangle = m_triangles.GetData(); - const CircularListElement * v0 = currentTriangle.m_vertices[0]; - const CircularListElement * v1 = currentTriangle.m_vertices[1]; - const CircularListElement * v2 = currentTriangle.m_vertices[2]; - const CircularListElement * e0 = currentTriangle.m_edges[0]; - const CircularListElement * e1 = currentTriangle.m_edges[1]; - const CircularListElement * e2 = currentTriangle.m_edges[2]; - - std::cout << "-> (" << v0->GetData().m_name << ", " << v1->GetData().m_name << ", "<< v2->GetData().m_name << ")" << std::endl; - - std::cout << "-> E0 (" << e0->GetData().m_vertices[0]->GetData().m_name << ", " - << e0->GetData().m_vertices[1]->GetData().m_name << ")" << std::endl; - std::cout << "-> E1 (" << e1->GetData().m_vertices[0]->GetData().m_name << ", " - << e1->GetData().m_vertices[1]->GetData().m_name << ")" << std::endl; - std::cout << "-> E2 (" << e2->GetData().m_vertices[0]->GetData().m_name << ", " - << e2->GetData().m_vertices[1]->GetData().m_name << ")" << std::endl; - m_triangles.Next(); - } - } - bool TMMesh::Save(const char *fileName) - { - std::ofstream fout(fileName); - std::cout << "Saving " << fileName << std::endl; - if (SaveVRML2(fout)) - { - fout.close(); - return true; - } - return false; - } - bool TMMesh::SaveVRML2(std::ofstream &fout) - { - return SaveVRML2(fout, Material()); - } - bool TMMesh::SaveVRML2(std::ofstream &fout, const Material & material) - { - if (fout.is_open()) - { - size_t nV = m_vertices.GetSize(); - size_t nT = m_triangles.GetSize(); - fout <<"#VRML V2.0 utf8" << std::endl; - fout <<"" << std::endl; - fout <<"# Vertices: " << nV << std::endl; - fout <<"# Triangles: " << nT << std::endl; - fout <<"" << std::endl; - fout <<"Group {" << std::endl; - fout <<" children [" << std::endl; - fout <<" Shape {" << std::endl; - fout <<" appearance Appearance {" << std::endl; - fout <<" material Material {" << std::endl; - fout <<" diffuseColor " << material.m_diffuseColor.X() << " " - << material.m_diffuseColor.Y() << " " - << material.m_diffuseColor.Z() << std::endl; - fout <<" ambientIntensity " << material.m_ambientIntensity << std::endl; - fout <<" specularColor " << material.m_specularColor.X() << " " - << material.m_specularColor.Y() << " " - << material.m_specularColor.Z() << std::endl; - fout <<" emissiveColor " << material.m_emissiveColor.X() << " " - << material.m_emissiveColor.Y() << " " - << material.m_emissiveColor.Z() << std::endl; - fout <<" shininess " << material.m_shininess << std::endl; - fout <<" transparency " << material.m_transparency << std::endl; - fout <<" }" << std::endl; - fout <<" }" << std::endl; - fout <<" geometry IndexedFaceSet {" << std::endl; - fout <<" ccw TRUE" << std::endl; - fout <<" solid TRUE" << std::endl; - fout <<" convex TRUE" << std::endl; - if (GetNVertices() > 0) { - fout <<" coord DEF co Coordinate {" << std::endl; - fout <<" point [" << std::endl; - for(size_t v = 0; v < nV; v++) - { - TMMVertex & currentVertex = m_vertices.GetData(); - fout <<" " << currentVertex.m_pos.X() << " " - << currentVertex.m_pos.Y() << " " - << currentVertex.m_pos.Z() << "," << std::endl; - currentVertex.m_id = v; - m_vertices.Next(); - } - fout <<" ]" << std::endl; - fout <<" }" << std::endl; - } - if (GetNTriangles() > 0) { - fout <<" coordIndex [ " << std::endl; - for(size_t f = 0; f < nT; f++) - { - TMMTriangle & currentTriangle = m_triangles.GetData(); - fout <<" " << currentTriangle.m_vertices[0]->GetData().m_id << ", " - << currentTriangle.m_vertices[1]->GetData().m_id << ", " - << currentTriangle.m_vertices[2]->GetData().m_id << ", -1," << std::endl; - m_triangles.Next(); - } - fout <<" ]" << std::endl; - } - fout <<" }" << std::endl; - fout <<" }" << std::endl; - fout <<" ]" << std::endl; - fout <<"}" << std::endl; - } - return true; - } - void TMMesh::GetIFS(Vec3 * const points, Vec3 * const triangles) - { - size_t nV = m_vertices.GetSize(); - size_t nT = m_triangles.GetSize(); - - for(size_t v = 0; v < nV; v++) - { - points[v] = m_vertices.GetData().m_pos; - m_vertices.GetData().m_id = v; - m_vertices.Next(); - } - for(size_t f = 0; f < nT; f++) - { - TMMTriangle & currentTriangle = m_triangles.GetData(); - triangles[f].X() = static_cast(currentTriangle.m_vertices[0]->GetData().m_id); - triangles[f].Y() = static_cast(currentTriangle.m_vertices[1]->GetData().m_id); - triangles[f].Z() = static_cast(currentTriangle.m_vertices[2]->GetData().m_id); - m_triangles.Next(); - } - } - void TMMesh::Clear() - { - m_vertices.Clear(); - m_edges.Clear(); - m_triangles.Clear(); - } - void TMMesh::Copy(TMMesh & mesh) - { - Clear(); - // updating the id's - size_t nV = mesh.m_vertices.GetSize(); - size_t nE = mesh. m_edges.GetSize(); - size_t nT = mesh.m_triangles.GetSize(); - for(size_t v = 0; v < nV; v++) - { - mesh.m_vertices.GetData().m_id = v; - mesh.m_vertices.Next(); - } - for(size_t e = 0; e < nE; e++) - { - mesh.m_edges.GetData().m_id = e; - mesh.m_edges.Next(); - - } - for(size_t f = 0; f < nT; f++) - { - mesh.m_triangles.GetData().m_id = f; - mesh.m_triangles.Next(); - } - // copying data - m_vertices = mesh.m_vertices; - m_edges = mesh.m_edges; - m_triangles = mesh.m_triangles; - - // generating mapping - CircularListElement ** vertexMap = new CircularListElement * [nV]; - CircularListElement ** edgeMap = new CircularListElement * [nE]; - CircularListElement ** triangleMap = new CircularListElement * [nT]; - for(size_t v = 0; v < nV; v++) - { - vertexMap[v] = m_vertices.GetHead(); - m_vertices.Next(); - } - for(size_t e = 0; e < nE; e++) - { - edgeMap[e] = m_edges.GetHead(); - m_edges.Next(); - } - for(size_t f = 0; f < nT; f++) - { - triangleMap[f] = m_triangles.GetHead(); - m_triangles.Next(); - } - - // updating pointers - for(size_t v = 0; v < nV; v++) - { - if (vertexMap[v]->GetData().m_duplicate) - { - vertexMap[v]->GetData().m_duplicate = edgeMap[vertexMap[v]->GetData().m_duplicate->GetData().m_id]; - } - } - for(size_t e = 0; e < nE; e++) - { - if (edgeMap[e]->GetData().m_newFace) - { - edgeMap[e]->GetData().m_newFace = triangleMap[edgeMap[e]->GetData().m_newFace->GetData().m_id]; - } - if (nT > 0) - { - for(int f = 0; f < 2; f++) - { - if (edgeMap[e]->GetData().m_triangles[f]) - { - edgeMap[e]->GetData().m_triangles[f] = triangleMap[edgeMap[e]->GetData().m_triangles[f]->GetData().m_id]; - } - } - } - for(int v = 0; v < 2; v++) - { - if (edgeMap[e]->GetData().m_vertices[v]) - { - edgeMap[e]->GetData().m_vertices[v] = vertexMap[edgeMap[e]->GetData().m_vertices[v]->GetData().m_id]; - } - } - } - for(size_t f = 0; f < nT; f++) - { - if (nE > 0) - { - for(int e = 0; e < 3; e++) - { - if (triangleMap[f]->GetData().m_edges[e]) - { - triangleMap[f]->GetData().m_edges[e] = edgeMap[triangleMap[f]->GetData().m_edges[e]->GetData().m_id]; - } - } - } - for(int v = 0; v < 3; v++) - { - if (triangleMap[f]->GetData().m_vertices[v]) - { - triangleMap[f]->GetData().m_vertices[v] = vertexMap[triangleMap[f]->GetData().m_vertices[v]->GetData().m_id]; - } - } - } - delete [] vertexMap; - delete [] edgeMap; - delete [] triangleMap; - - } - long IntersectRayTriangle(const Vec3 & P0, const Vec3 & dir, - const Vec3 & V0, const Vec3 & V1, - const Vec3 & V2, double &t) - { - Vec3 edge1, edge2, edge3; - double det, invDet; - edge1 = V1 - V2; - edge2 = V2 - V0; - Vec3 pvec = dir ^ edge2; - det = edge1 * pvec; - if (det == 0.0) - return 0; - invDet = 1.0/det; - Vec3 tvec = P0 - V0; - Vec3 qvec = tvec ^ edge1; - t = (edge2 * qvec) * invDet; - if (t < 0.0) - { - return 0; - } - edge3 = V0 - V1; - Vec3 I(P0 + t * dir); - Vec3 s0 = (I-V0) ^ edge3; - Vec3 s1 = (I-V1) ^ edge1; - Vec3 s2 = (I-V2) ^ edge2; - if (s0*s1 > -1e-9 && s2*s1 > -1e-9) - { - return 1; - } - return 0; - } - - bool IntersectLineLine(const Vec3 & p1, const Vec3 & p2, - const Vec3 & p3, const Vec3 & p4, - Vec3 & pa, Vec3 & pb, - double & mua, double & mub) - { - Vec3 p13,p43,p21; - double d1343,d4321,d1321,d4343,d2121; - double numer,denom; - - p13.X() = p1.X() - p3.X(); - p13.Y() = p1.Y() - p3.Y(); - p13.Z() = p1.Z() - p3.Z(); - p43.X() = p4.X() - p3.X(); - p43.Y() = p4.Y() - p3.Y(); - p43.Z() = p4.Z() - p3.Z(); - if (p43.X()==0.0 && p43.Y()==0.0 && p43.Z()==0.0) - return false; - p21.X() = p2.X() - p1.X(); - p21.Y() = p2.Y() - p1.Y(); - p21.Z() = p2.Z() - p1.Z(); - if (p21.X()==0.0 && p21.Y()==0.0 && p21.Z()==0.0) - return false; - - d1343 = p13.X() * p43.X() + p13.Y() * p43.Y() + p13.Z() * p43.Z(); - d4321 = p43.X() * p21.X() + p43.Y() * p21.Y() + p43.Z() * p21.Z(); - d1321 = p13.X() * p21.X() + p13.Y() * p21.Y() + p13.Z() * p21.Z(); - d4343 = p43.X() * p43.X() + p43.Y() * p43.Y() + p43.Z() * p43.Z(); - d2121 = p21.X() * p21.X() + p21.Y() * p21.Y() + p21.Z() * p21.Z(); - - denom = d2121 * d4343 - d4321 * d4321; - if (denom==0.0) - return false; - numer = d1343 * d4321 - d1321 * d4343; - - mua = numer / denom; - mub = (d1343 + d4321 * (mua)) / d4343; - - pa.X() = p1.X() + mua * p21.X(); - pa.Y() = p1.Y() + mua * p21.Y(); - pa.Z() = p1.Z() + mua * p21.Z(); - pb.X() = p3.X() + mub * p43.X(); - pb.Y() = p3.Y() + mub * p43.Y(); - pb.Z() = p3.Z() + mub * p43.Z(); - - return true; - } - - long IntersectRayTriangle2(const Vec3 & P0, const Vec3 & dir, - const Vec3 & V0, const Vec3 & V1, - const Vec3 & V2, double &r) - { - Vec3 u, v, n; // triangle vectors - Vec3 w0, w; // ray vectors - double a, b; // params to calc ray-plane intersect - - // get triangle edge vectors and plane normal - u = V1 - V0; - v = V2 - V0; - n = u ^ v; // cross product - if (n.GetNorm() == 0.0) // triangle is degenerate - return -1; // do not deal with this case - - w0 = P0 - V0; - a = - n * w0; - b = n * dir; - if (fabs(b) <= 0.0) { // ray is parallel to triangle plane - if (a == 0.0) // ray lies in triangle plane - return 2; - else return 0; // ray disjoint from plane - } - - // get intersect point of ray with triangle plane - r = a / b; - if (r < 0.0) // ray goes away from triangle - return 0; // => no intersect - // for a segment, also test if (r > 1.0) => no intersect - - Vec3 I = P0 + r * dir; // intersect point of ray and plane - - // is I inside T? - double uu, uv, vv, wu, wv, D; - uu = u * u; - uv = u * v; - vv = v * v; - w = I - V0; - wu = w * u; - wv = w * v; - D = uv * uv - uu * vv; - - // get and test parametric coords - double s, t; - s = (uv * wv - vv * wu) / D; - if (s < 0.0 || s > 1.0) // I is outside T - return 0; - t = (uv * wu - uu * wv) / D; - if (t < 0.0 || (s + t) > 1.0) // I is outside T - return 0; - return 1; // I is in T - } - - - bool TMMesh::CheckConsistancy() - { - size_t nE = m_edges.GetSize(); - size_t nT = m_triangles.GetSize(); - for(size_t e = 0; e < nE; e++) - { - for(int f = 0; f < 2; f++) - { - if (!m_edges.GetHead()->GetData().m_triangles[f]) - { - return false; - } - } - m_edges.Next(); - } - - for(size_t f = 0; f < nT; f++) - { - for(int e = 0; e < 3; e++) - { - int found = 0; - for(int k = 0; k < 2; k++) - { - if (m_triangles.GetHead()->GetData().m_edges[e]->GetData().m_triangles[k] == m_triangles.GetHead()) - { - found++; - } - } - if (found != 1) - { - return false; - } - } - m_triangles.Next(); - } - - return true; - } - bool TMMesh::Normalize() - { - size_t nV = m_vertices.GetSize(); - if (nV == 0) - { - return false; - } - m_barycenter = m_vertices.GetHead()->GetData().m_pos; - Vec3 min = m_barycenter; - Vec3 max = m_barycenter; - Real x, y, z; - for(size_t v = 1; v < nV; v++) - { - m_barycenter += m_vertices.GetHead()->GetData().m_pos; - x = m_vertices.GetHead()->GetData().m_pos.X(); - y = m_vertices.GetHead()->GetData().m_pos.Y(); - z = m_vertices.GetHead()->GetData().m_pos.Z(); - if ( x < min.X()) min.X() = x; - else if ( x > max.X()) max.X() = x; - if ( y < min.Y()) min.Y() = y; - else if ( y > max.Y()) max.Y() = y; - if ( z < min.Z()) min.Z() = z; - else if ( z > max.Z()) max.Z() = z; - m_vertices.Next(); - } - m_barycenter /= static_cast(nV); - m_diag = static_cast(0.001 * (max-min).GetNorm()); - const Real invDiag = static_cast(1.0 / m_diag); - if (m_diag != 0.0) - { - for(size_t v = 0; v < nV; v++) - { - m_vertices.GetHead()->GetData().m_pos = (m_vertices.GetHead()->GetData().m_pos - m_barycenter) * invDiag; - m_vertices.Next(); - } - } - return true; - } - bool TMMesh::Denormalize() - { - size_t nV = m_vertices.GetSize(); - if (nV == 0) - { - return false; - } - if (m_diag != 0.0) - { - for(size_t v = 0; v < nV; v++) - { - m_vertices.GetHead()->GetData().m_pos = m_vertices.GetHead()->GetData().m_pos * m_diag + m_barycenter; - m_vertices.Next(); - } - } - return false; - } -} diff --git a/extern/bullet/src/Extras/HACD/hacdManifoldMesh.h b/extern/bullet/src/Extras/HACD/hacdManifoldMesh.h deleted file mode 100644 index 318ecbab6e9d..000000000000 --- a/extern/bullet/src/Extras/HACD/hacdManifoldMesh.h +++ /dev/null @@ -1,250 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) -All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -*/ - -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) - All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#pragma once -#ifndef HACD_MANIFOLD_MESH_H -#define HACD_MANIFOLD_MESH_H -#include -#include -#include "hacdVersion.h" -#include "hacdCircularList.h" -#include "hacdVector.h" -#include -namespace HACD -{ - class TMMTriangle; - class TMMEdge; - class TMMesh; - class ICHull; - class HACD; - - class DPoint - { - public: - DPoint(Real dist=0, bool computed=false, bool distOnly=false) - :m_dist(dist), - m_computed(computed), - m_distOnly(distOnly){}; - ~DPoint(){}; - private: - Real m_dist; - bool m_computed; - bool m_distOnly; - friend class TMMTriangle; - friend class TMMesh; - friend class GraphVertex; - friend class GraphEdge; - friend class Graph; - friend class ICHull; - friend class HACD; - }; - - //! Vertex data structure used in a triangular manifold mesh (TMM). - class TMMVertex - { - public: - TMMVertex(void); - ~TMMVertex(void); - - private: - Vec3 m_pos; - long m_name; - size_t m_id; - CircularListElement * m_duplicate; // pointer to incident cone edge (or NULL) - bool m_onHull; - bool m_tag; - TMMVertex(const TMMVertex & rhs); - - friend class HACD; - friend class ICHull; - friend class TMMesh; - friend class TMMTriangle; - friend class TMMEdge; - }; - - //! Edge data structure used in a triangular manifold mesh (TMM). - class TMMEdge - { - public: - TMMEdge(void); - ~TMMEdge(void); - private: - size_t m_id; - CircularListElement * m_triangles[2]; - CircularListElement * m_vertices[2]; - CircularListElement * m_newFace; - - - TMMEdge(const TMMEdge & rhs); - - friend class HACD; - friend class ICHull; - friend class TMMTriangle; - friend class TMMVertex; - friend class TMMesh; - }; - - //! Triangle data structure used in a triangular manifold mesh (TMM). - class TMMTriangle - { - public: - TMMTriangle(void); - ~TMMTriangle(void); - private: - size_t m_id; - CircularListElement * m_edges[3]; - CircularListElement * m_vertices[3]; - std::set m_incidentPoints; - bool m_visible; - - TMMTriangle(const TMMTriangle & rhs); - - friend class HACD; - friend class ICHull; - friend class TMMesh; - friend class TMMVertex; - friend class TMMEdge; - }; - - class Material - { - public: - Material(void); - ~Material(void){} -// private: - Vec3 m_diffuseColor; - double m_ambientIntensity; - Vec3 m_specularColor; - Vec3 m_emissiveColor; - double m_shininess; - double m_transparency; - - friend class TMMesh; - friend class HACD; - }; - - //! triangular manifold mesh data structure. - class TMMesh - { - public: - - //! Returns the number of vertices> - inline size_t GetNVertices() const { return m_vertices.GetSize();} - //! Returns the number of edges - inline size_t GetNEdges() const { return m_edges.GetSize();} - //! Returns the number of triangles - inline size_t GetNTriangles() const { return m_triangles.GetSize();} - //! Returns the vertices circular list - inline const CircularList & GetVertices() const { return m_vertices;} - //! Returns the edges circular list - inline const CircularList & GetEdges() const { return m_edges;} - //! Returns the triangles circular list - inline const CircularList & GetTriangles() const { return m_triangles;} - //! Returns the vertices circular list - inline CircularList & GetVertices() { return m_vertices;} - //! Returns the edges circular list - inline CircularList & GetEdges() { return m_edges;} - //! Returns the triangles circular list - inline CircularList & GetTriangles() { return m_triangles;} - //! Add vertex to the mesh - CircularListElement * AddVertex() {return m_vertices.Add();} - //! Add vertex to the mesh - CircularListElement * AddEdge() {return m_edges.Add();} - //! Add vertex to the mesh - CircularListElement * AddTriangle() {return m_triangles.Add();} - //! Print mesh information - void Print(); - //! - void GetIFS(Vec3 * const points, Vec3 * const triangles); - //! Save mesh - bool Save(const char *fileName); - //! Save mesh to VRML 2.0 format - bool SaveVRML2(std::ofstream &fout); - //! Save mesh to VRML 2.0 format - bool SaveVRML2(std::ofstream &fout, const Material & material); - //! - void Clear(); - //! - void Copy(TMMesh & mesh); - //! - bool CheckConsistancy(); - //! - bool Normalize(); - //! - bool Denormalize(); - //! Constructor - TMMesh(void); - //! Destructor - virtual ~TMMesh(void); - - private: - CircularList m_vertices; - CircularList m_edges; - CircularList m_triangles; - Real m_diag; //>! length of the BB diagonal - Vec3 m_barycenter; //>! barycenter of the mesh - - // not defined - TMMesh(const TMMesh & rhs); - friend class ICHull; - friend class HACD; - }; - //! IntersectRayTriangle(): intersect a ray with a 3D triangle - //! Input: a ray R, and a triangle T - //! Output: *I = intersection point (when it exists) - //! 0 = disjoint (no intersect) - //! 1 = intersect in unique point I1 - long IntersectRayTriangle( const Vec3 & P0, const Vec3 & dir, - const Vec3 & V0, const Vec3 & V1, - const Vec3 & V2, double &t); - - // intersect_RayTriangle(): intersect a ray with a 3D triangle - // Input: a ray R, and a triangle T - // Output: *I = intersection point (when it exists) - // Return: -1 = triangle is degenerate (a segment or point) - // 0 = disjoint (no intersect) - // 1 = intersect in unique point I1 - // 2 = are in the same plane - long IntersectRayTriangle2(const Vec3 & P0, const Vec3 & dir, - const Vec3 & V0, const Vec3 & V1, - const Vec3 & V2, double &r); - - /* - Calculate the line segment PaPb that is the shortest route between - two lines P1P2 and P3P4. Calculate also the values of mua and mub where - Pa = P1 + mua (P2 - P1) - Pb = P3 + mub (P4 - P3) - Return FALSE if no solution exists. - */ - bool IntersectLineLine(const Vec3 & p1, const Vec3 & p2, - const Vec3 & p3, const Vec3 & p4, - Vec3 & pa, Vec3 & pb, - double & mua, double &mub); -} -#endif diff --git a/extern/bullet/src/Extras/HACD/hacdVector.h b/extern/bullet/src/Extras/HACD/hacdVector.h deleted file mode 100644 index bb0858ba5551..000000000000 --- a/extern/bullet/src/Extras/HACD/hacdVector.h +++ /dev/null @@ -1,67 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) - All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#pragma once -#ifndef HACD_VECTOR_H -#define HACD_VECTOR_H -#include -#include -#include "hacdVersion.h" - -namespace HACD -{ - typedef double Real; - //! Vector dim 3. - template < typename T > class Vec3 - { - public: - T & X(); - T & Y(); - T & Z(); - const T & X() const; - const T & Y() const; - const T & Z() const; - void Normalize(); - T GetNorm() const; - void operator= (const Vec3 & rhs); - void operator+=(const Vec3 & rhs); - void operator-=(const Vec3 & rhs); - void operator-=(T a); - void operator+=(T a); - void operator/=(T a); - void operator*=(T a); - Vec3 operator^ (const Vec3 & rhs) const; - T operator* (const Vec3 & rhs) const; - Vec3 operator+ (const Vec3 & rhs) const; - Vec3 operator- (const Vec3 & rhs) const; - Vec3 operator- () const; - Vec3 operator* (T rhs) const; - Vec3 operator/ (T rhs) const; - Vec3(); - Vec3(T a); - Vec3(T x, T y, T z); - Vec3(const Vec3 & rhs); - /*virtual*/ ~Vec3(void); - - private: - T m_data[3]; - }; - template - bool Colinear(const Vec3 & a, const Vec3 & b, const Vec3 & c); - template - const T Volume(const Vec3 & a, const Vec3 & b, const Vec3 & c, const Vec3 & d); - -} -#include "hacdVector.inl" // template implementation -#endif diff --git a/extern/bullet/src/Extras/HACD/hacdVector.inl b/extern/bullet/src/Extras/HACD/hacdVector.inl deleted file mode 100644 index b1f0c1b2a3f3..000000000000 --- a/extern/bullet/src/Extras/HACD/hacdVector.inl +++ /dev/null @@ -1,178 +0,0 @@ -#pragma once -#ifndef HACD_VECTOR_INL -#define HACD_VECTOR_INL -namespace HACD -{ - template - inline Vec3 operator*(T lhs, const Vec3 & rhs) - { - return Vec3(lhs * rhs.X(), lhs * rhs.Y(), lhs * rhs.Z()); - } - template - inline T & Vec3::X() - { - return m_data[0]; - } - template - inline T & Vec3::Y() - { - return m_data[1]; - } - template - inline T & Vec3::Z() - { - return m_data[2]; - } - template - inline const T & Vec3::X() const - { - return m_data[0]; - } - template - inline const T & Vec3::Y() const - { - return m_data[1]; - } - template - inline const T & Vec3::Z() const - { - return m_data[2]; - } - template - inline void Vec3::Normalize() - { - T n = sqrt(m_data[0]*m_data[0]+m_data[1]*m_data[1]+m_data[2]*m_data[2]); - if (n != 0.0) (*this) /= n; - } - template - inline T Vec3::GetNorm() const - { - return sqrt(m_data[0]*m_data[0]+m_data[1]*m_data[1]+m_data[2]*m_data[2]); - } - template - inline void Vec3::operator= (const Vec3 & rhs) - { - this->m_data[0] = rhs.m_data[0]; - this->m_data[1] = rhs.m_data[1]; - this->m_data[2] = rhs.m_data[2]; - } - template - inline void Vec3::operator+=(const Vec3 & rhs) - { - this->m_data[0] += rhs.m_data[0]; - this->m_data[1] += rhs.m_data[1]; - this->m_data[2] += rhs.m_data[2]; - } - template - inline void Vec3::operator-=(const Vec3 & rhs) - { - this->m_data[0] -= rhs.m_data[0]; - this->m_data[1] -= rhs.m_data[1]; - this->m_data[2] -= rhs.m_data[2]; - } - template - inline void Vec3::operator-=(T a) - { - this->m_data[0] -= a; - this->m_data[1] -= a; - this->m_data[2] -= a; - } - template - inline void Vec3::operator+=(T a) - { - this->m_data[0] += a; - this->m_data[1] += a; - this->m_data[2] += a; - } - template - inline void Vec3::operator/=(T a) - { - this->m_data[0] /= a; - this->m_data[1] /= a; - this->m_data[2] /= a; - } - template - inline void Vec3::operator*=(T a) - { - this->m_data[0] *= a; - this->m_data[1] *= a; - this->m_data[2] *= a; - } - template - inline Vec3 Vec3::operator^ (const Vec3 & rhs) const - { - return Vec3(m_data[1] * rhs.m_data[2] - m_data[2] * rhs.m_data[1], - m_data[2] * rhs.m_data[0] - m_data[0] * rhs.m_data[2], - m_data[0] * rhs.m_data[1] - m_data[1] * rhs.m_data[0]); - } - template - inline T Vec3::operator*(const Vec3 & rhs) const - { - return (m_data[0] * rhs.m_data[0] + m_data[1] * rhs.m_data[1] + m_data[2] * rhs.m_data[2]); - } - template - inline Vec3 Vec3::operator+(const Vec3 & rhs) const - { - return Vec3(m_data[0] + rhs.m_data[0],m_data[1] + rhs.m_data[1],m_data[2] + rhs.m_data[2]); - } - template - inline Vec3 Vec3::operator-(const Vec3 & rhs) const - { - return Vec3(m_data[0] - rhs.m_data[0],m_data[1] - rhs.m_data[1],m_data[2] - rhs.m_data[2]) ; - } - template - inline Vec3 Vec3::operator-() const - { - return Vec3(-m_data[0],-m_data[1],-m_data[2]) ; - } - - template - inline Vec3 Vec3::operator*(T rhs) const - { - return Vec3(rhs * this->m_data[0], rhs * this->m_data[1], rhs * this->m_data[2]); - } - template - inline Vec3 Vec3::operator/ (T rhs) const - { - return Vec3(m_data[0] / rhs, m_data[1] / rhs, m_data[2] / rhs); - } - template - inline Vec3::Vec3(T a) - { - m_data[0] = m_data[1] = m_data[2] = a; - } - template - inline Vec3::Vec3(T x, T y, T z) - { - m_data[0] = x; - m_data[1] = y; - m_data[2] = z; - } - template - inline Vec3::Vec3(const Vec3 & rhs) - { - m_data[0] = rhs.m_data[0]; - m_data[1] = rhs.m_data[1]; - m_data[2] = rhs.m_data[2]; - } - template - inline Vec3::~Vec3(void){}; - - template - inline Vec3::Vec3() {} - - template - inline bool Colinear(const Vec3 & a, const Vec3 & b, const Vec3 & c) - { - return ((c.Z() - a.Z()) * (b.Y() - a.Y()) - (b.Z() - a.Z()) * (c.Y() - a.Y()) == 0.0 /*EPS*/) && - ((b.Z() - a.Z()) * (c.X() - a.X()) - (b.X() - a.X()) * (c.Z() - a.Z()) == 0.0 /*EPS*/) && - ((b.X() - a.X()) * (c.Y() - a.Y()) - (b.Y() - a.Y()) * (c.X() - a.X()) == 0.0 /*EPS*/); - } - - template - inline const T Volume(const Vec3 & a, const Vec3 & b, const Vec3 & c, const Vec3 & d) - { - return (a-d) * ((b-d) ^ (c-d)); - } -} -#endif //HACD_VECTOR_INL diff --git a/extern/bullet/src/Extras/HACD/hacdVersion.h b/extern/bullet/src/Extras/HACD/hacdVersion.h deleted file mode 100644 index c9f7f28da95f..000000000000 --- a/extern/bullet/src/Extras/HACD/hacdVersion.h +++ /dev/null @@ -1,20 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) - All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#pragma once -#ifndef HACD_VERSION_H -#define HACD_VERSION_H -#define HACD_VERSION_MAJOR 0 -#define HACD_VERSION_MINOR 0 -#endif \ No newline at end of file diff --git a/extern/bullet/src/Extras/HACD/premake4.lua b/extern/bullet/src/Extras/HACD/premake4.lua deleted file mode 100644 index c2f03c1735f9..000000000000 --- a/extern/bullet/src/Extras/HACD/premake4.lua +++ /dev/null @@ -1,12 +0,0 @@ - project "HACD" - - kind "StaticLib" - - includedirs {"."} - if os.is("Linux") then - buildoptions{"-fPIC"} - end - files { - "**.cpp", - "**.h" - } \ No newline at end of file diff --git a/extern/bullet/src/Extras/InverseDynamics/BulletInverseDynamicsUtilsCommon.h b/extern/bullet/src/Extras/InverseDynamics/BulletInverseDynamicsUtilsCommon.h deleted file mode 100644 index 25e77cda63dd..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/BulletInverseDynamicsUtilsCommon.h +++ /dev/null @@ -1,17 +0,0 @@ -#ifndef BULLET_INVERSE_DYNAMICS_UTILS_COMMON_H -#define BULLET_INVERSE_DYNAMICS_UTILS_COMMON_H -#include "CoilCreator.hpp" -#include "MultiBodyTreeCreator.hpp" -#include "btMultiBodyFromURDF.hpp" -#include "DillCreator.hpp" -#include "MultiBodyTreeDebugGraph.hpp" -#include "btMultiBodyTreeCreator.hpp" -#include "IDRandomUtil.hpp" -#include "SimpleTreeCreator.hpp" -#include "invdyn_bullet_comparison.hpp" -#include "MultiBodyNameMap.hpp" -#include "User2InternalIndex.hpp" - -#endif//BULLET_INVERSE_DYNAMICS_UTILS_COMMON_H - - diff --git a/extern/bullet/src/Extras/InverseDynamics/CMakeLists.txt b/extern/bullet/src/Extras/InverseDynamics/CMakeLists.txt deleted file mode 100644 index 22e953a44e21..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/CMakeLists.txt +++ /dev/null @@ -1,50 +0,0 @@ -INCLUDE_DIRECTORIES( - ${BULLET_PHYSICS_SOURCE_DIR}/src -) - -ADD_LIBRARY( -BulletInverseDynamicsUtils -CloneTreeCreator.cpp -CoilCreator.cpp -MultiBodyTreeCreator.cpp -btMultiBodyTreeCreator.cpp -DillCreator.cpp -MultiBodyTreeDebugGraph.cpp -invdyn_bullet_comparison.cpp -IDRandomUtil.cpp -RandomTreeCreator.cpp -SimpleTreeCreator.cpp -MultiBodyNameMap.cpp -User2InternalIndex.cpp -) - -SET_TARGET_PROPERTIES(BulletInverseDynamicsUtils PROPERTIES VERSION ${BULLET_VERSION}) -SET_TARGET_PROPERTIES(BulletInverseDynamicsUtils PROPERTIES SOVERSION ${BULLET_VERSION}) - -IF (BUILD_SHARED_LIBS) - TARGET_LINK_LIBRARIES(BulletInverseDynamicsUtils BulletInverseDynamics BulletDynamics BulletCollision Bullet3Common LinearMath) -ENDIF (BUILD_SHARED_LIBS) - -IF (INSTALL_EXTRA_LIBS) - IF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES) - #FILES_MATCHING requires CMake 2.6 - IF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5) - IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - INSTALL(TARGETS BulletInverseDynamicsUtils DESTINATION .) - ELSE (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - INSTALL(TARGETS BulletInverseDynamicsUtils - RUNTIME DESTINATION bin - LIBRARY DESTINATION lib${LIB_SUFFIX} - ARCHIVE DESTINATION lib${LIB_SUFFIX}) - INSTALL(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} -DESTINATION ${INCLUDE_INSTALL_DIR} FILES_MATCHING PATTERN "*.h" PATTERN -".svn" EXCLUDE PATTERN "CMakeFiles" EXCLUDE) - ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - ENDIF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5) - - IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - SET_TARGET_PROPERTIES(BulletInverseDynamicsUtils PROPERTIES FRAMEWORK true) - SET_TARGET_PROPERTIES(BulletInverseDynamicsUtils PROPERTIES PUBLIC_HEADER "BulletInverseDynamicsUtilsCommon.h" ) - ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - ENDIF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES) -ENDIF (INSTALL_EXTRA_LIBS) diff --git a/extern/bullet/src/Extras/InverseDynamics/CloneTreeCreator.cpp b/extern/bullet/src/Extras/InverseDynamics/CloneTreeCreator.cpp deleted file mode 100644 index d267282a4952..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/CloneTreeCreator.cpp +++ /dev/null @@ -1,49 +0,0 @@ -#include "CloneTreeCreator.hpp" - -#include - -namespace btInverseDynamics { -#define CHECK_NULLPTR() \ - do { \ - if (m_reference == 0x0) { \ - bt_id_error_message("m_reference == 0x0\n"); \ - return -1; \ - } \ - } while (0) - -#define TRY(x) \ - do { \ - if (x == -1) { \ - bt_id_error_message("error calling " #x "\n"); \ - return -1; \ - } \ - } while (0) -CloneTreeCreator::CloneTreeCreator(const MultiBodyTree* reference) { m_reference = reference; } - -CloneTreeCreator::~CloneTreeCreator() {} - -int CloneTreeCreator::getNumBodies(int* num_bodies) const { - CHECK_NULLPTR(); - *num_bodies = m_reference->numBodies(); - return 0; -} - -int CloneTreeCreator::getBody(const int body_index, int* parent_index, JointType* joint_type, - vec3* parent_r_parent_body_ref, mat33* body_T_parent_ref, - vec3* body_axis_of_motion, idScalar* mass, vec3* body_r_body_com, - mat33* body_I_body, int* user_int, void** user_ptr) const { - CHECK_NULLPTR(); - TRY(m_reference->getParentIndex(body_index, parent_index)); - TRY(m_reference->getJointType(body_index, joint_type)); - TRY(m_reference->getParentRParentBodyRef(body_index, parent_r_parent_body_ref)); - TRY(m_reference->getBodyTParentRef(body_index, body_T_parent_ref)); - TRY(m_reference->getBodyAxisOfMotion(body_index, body_axis_of_motion)); - TRY(m_reference->getBodyMass(body_index, mass)); - TRY(m_reference->getBodyFirstMassMoment(body_index, body_r_body_com)); - TRY(m_reference->getBodySecondMassMoment(body_index, body_I_body)); - TRY(m_reference->getUserInt(body_index, user_int)); - TRY(m_reference->getUserPtr(body_index, user_ptr)); - - return 0; -} -} diff --git a/extern/bullet/src/Extras/InverseDynamics/CloneTreeCreator.hpp b/extern/bullet/src/Extras/InverseDynamics/CloneTreeCreator.hpp deleted file mode 100644 index cb96d56b492d..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/CloneTreeCreator.hpp +++ /dev/null @@ -1,27 +0,0 @@ -#ifndef CLONETREE_CREATOR_HPP_ -#define CLONETREE_CREATOR_HPP_ - -#include "BulletInverseDynamics/IDConfig.hpp" -#include "MultiBodyTreeCreator.hpp" - -namespace btInverseDynamics { -/// Generate an identical multibody tree from a reference system. -class CloneTreeCreator : public MultiBodyTreeCreator { -public: - /// ctor - /// @param reference the MultiBodyTree to clone - CloneTreeCreator(const MultiBodyTree*reference); - ~CloneTreeCreator(); - ///\copydoc MultiBodyTreeCreator::getNumBodies - int getNumBodies(int* num_bodies) const; - ///\copydoc MultiBodyTreeCreator::getBody - int getBody(const int body_index, int* parent_index, JointType* joint_type, - vec3* parent_r_parent_body_ref, mat33* body_T_parent_ref, vec3* body_axis_of_motion, - idScalar* mass, vec3* body_r_body_com, mat33* body_I_body, int* user_int, - void** user_ptr) const; - -private: - const MultiBodyTree *m_reference; -}; -} -#endif // CLONETREE_CREATOR_HPP_ diff --git a/extern/bullet/src/Extras/InverseDynamics/CoilCreator.cpp b/extern/bullet/src/Extras/InverseDynamics/CoilCreator.cpp deleted file mode 100644 index ce37a9922a95..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/CoilCreator.cpp +++ /dev/null @@ -1,67 +0,0 @@ -#include - -#include "CoilCreator.hpp" - -namespace btInverseDynamics { -CoilCreator::CoilCreator(int n) : m_num_bodies(n), m_parent(n) { - for (int i = 0; i < m_num_bodies; i++) { - m_parent[i] = i - 1; - } - - // DH parameters (that's what's in the paper ...) - const idScalar theta_DH = 0; - const idScalar d_DH = 0.0; - const idScalar a_DH = 1.0 / m_num_bodies; - const idScalar alpha_DH = 5.0 * BT_ID_PI / m_num_bodies; - getVecMatFromDH(theta_DH, d_DH, a_DH, alpha_DH, &m_parent_r_parent_body_ref, - &m_body_T_parent_ref); - // always z-axis - m_body_axis_of_motion(0) = 0.0; - m_body_axis_of_motion(1) = 0.0; - m_body_axis_of_motion(2) = 1.0; - - m_mass = 1.0 / m_num_bodies; - m_body_r_body_com(0) = 1.0 / (2.0 * m_num_bodies); - m_body_r_body_com(1) = 0.0; - m_body_r_body_com(2) = 0.0; - - m_body_I_body(0, 0) = 1e-4 / (2.0 * m_num_bodies); - m_body_I_body(0, 1) = 0.0; - m_body_I_body(0, 2) = 0.0; - m_body_I_body(1, 0) = 0.0; - m_body_I_body(1, 1) = (3e-4 + 4.0 / BT_ID_POW(m_num_bodies, 2)) / (12.0 * m_num_bodies); - m_body_I_body(1, 2) = 0.0; - m_body_I_body(2, 0) = 0.0; - m_body_I_body(2, 1) = 0.0; - m_body_I_body(2, 2) = m_body_I_body(1, 1); -} - -CoilCreator::~CoilCreator() {} - -int CoilCreator::getNumBodies(int* num_bodies) const { - *num_bodies = m_num_bodies; - return 0; -} - -int CoilCreator::getBody(int body_index, int* parent_index, JointType* joint_type, - vec3* parent_r_parent_body_ref, mat33* body_T_parent_ref, - vec3* body_axis_of_motion, idScalar* mass, vec3* body_r_body_com, - mat33* body_I_body, int* user_int, void** user_ptr) const { - if (body_index < 0 || body_index >= m_num_bodies) { - bt_id_error_message("invalid body index %d\n", body_index); - return -1; - } - *parent_index = m_parent[body_index]; - *joint_type = REVOLUTE; - *parent_r_parent_body_ref = m_parent_r_parent_body_ref; - *body_T_parent_ref = m_body_T_parent_ref; - *body_axis_of_motion = m_body_axis_of_motion; - *mass = m_mass; - *body_r_body_com = m_body_r_body_com; - *body_I_body = m_body_I_body; - - *user_int = 0; - *user_ptr = 0; - return 0; -} -} diff --git a/extern/bullet/src/Extras/InverseDynamics/CoilCreator.hpp b/extern/bullet/src/Extras/InverseDynamics/CoilCreator.hpp deleted file mode 100644 index a57ee3595ae2..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/CoilCreator.hpp +++ /dev/null @@ -1,40 +0,0 @@ -#ifndef COILCREATOR_HPP_ -#define COILCREATOR_HPP_ - -#include "MultiBodyTreeCreator.hpp" - -namespace btInverseDynamics { - -/// Creator class for building a "coil" system as intruduced as benchmark example in -/// Featherstone (1999), "A Divide-and-Conquer Articulated-Body Algorithm for Parallel O(log(n)) -/// Calculation of Rigid-Body Dynamics. Part 2: Trees, Loops, and Accuracy.", The International -/// Journal of Robotics Research 18 (9): 876–892. doi : 10.1177 / 02783649922066628. -/// -/// This is a serial chain, with an initial configuration resembling a coil. -class CoilCreator : public MultiBodyTreeCreator { -public: - /// ctor. - /// @param n the number of bodies in the system - CoilCreator(int n); - /// dtor - ~CoilCreator(); - // \copydoc MultiBodyTreeCreator::getNumBodies - int getNumBodies(int* num_bodies) const; - // \copydoc MultiBodyTreeCreator::getBody - int getBody(const int body_index, int* parent_index, JointType* joint_type, - vec3* parent_r_parent_body_ref, mat33* body_T_parent_ref, vec3* body_axis_of_motion, - idScalar* mass, vec3* body_r_body_com, mat33* body_I_body, int* user_int, - void** user_ptr) const; - -private: - int m_num_bodies; - std::vector m_parent; - vec3 m_parent_r_parent_body_ref; - mat33 m_body_T_parent_ref; - vec3 m_body_axis_of_motion; - idScalar m_mass; - vec3 m_body_r_body_com; - mat33 m_body_I_body; -}; -} -#endif diff --git a/extern/bullet/src/Extras/InverseDynamics/DillCreator.cpp b/extern/bullet/src/Extras/InverseDynamics/DillCreator.cpp deleted file mode 100644 index 17f30dcd504c..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/DillCreator.cpp +++ /dev/null @@ -1,124 +0,0 @@ -#include "DillCreator.hpp" -#include -namespace btInverseDynamics { - -DillCreator::DillCreator(int level) - : m_level(level), - m_num_bodies(BT_ID_POW(2, level)) - { - m_parent.resize(m_num_bodies); - m_parent_r_parent_body_ref.resize(m_num_bodies); - m_body_T_parent_ref.resize(m_num_bodies); - m_body_axis_of_motion.resize(m_num_bodies); - m_mass.resize(m_num_bodies); - m_body_r_body_com.resize(m_num_bodies); - m_body_I_body.resize(m_num_bodies); - - // generate names (for debugging) - for (int i = 0; i < m_num_bodies; i++) { - m_parent[i] = i - 1; - - // all z-axis (DH convention) - m_body_axis_of_motion[i](0) = 0.0; - m_body_axis_of_motion[i](1) = 0.0; - m_body_axis_of_motion[i](2) = 1.0; - } - - // recursively build data structures - m_current_body = 0; - const int parent = -1; - const idScalar d_DH = 0.0; - const idScalar a_DH = 0.0; - const idScalar alpha_DH = 0.0; - - if (-1 == recurseDill(m_level, parent, d_DH, a_DH, alpha_DH)) { - bt_id_error_message("recurseDill failed\n"); - abort(); - } -} - -DillCreator::~DillCreator() {} - -int DillCreator::getNumBodies(int* num_bodies) const { - *num_bodies = m_num_bodies; - return 0; -} - -int DillCreator::getBody(const int body_index, int* parent_index, JointType* joint_type, - vec3* parent_r_parent_body_ref, mat33* body_T_parent_ref, - vec3* body_axis_of_motion, idScalar* mass, vec3* body_r_body_com, - mat33* body_I_body, int* user_int, void** user_ptr) const { - if (body_index < 0 || body_index >= m_num_bodies) { - bt_id_error_message("invalid body index %d\n", body_index); - return -1; - } - *parent_index = m_parent[body_index]; - *joint_type = REVOLUTE; - *parent_r_parent_body_ref = m_parent_r_parent_body_ref[body_index]; - *body_T_parent_ref = m_body_T_parent_ref[body_index]; - *body_axis_of_motion = m_body_axis_of_motion[body_index]; - *mass = m_mass[body_index]; - *body_r_body_com = m_body_r_body_com[body_index]; - *body_I_body = m_body_I_body[body_index]; - - *user_int = 0; - *user_ptr = 0; - return 0; -} - -int DillCreator::recurseDill(const int level, const int parent, const idScalar d_DH_in, - const idScalar a_DH_in, const idScalar alpha_DH_in) { - if (level < 0) { - bt_id_error_message("invalid level parameter (%d)\n", level); - return -1; - } - - if (m_current_body >= m_num_bodies || m_current_body < 0) { - bt_id_error_message("invalid body parameter (%d, num_bodies: %d)\n", m_current_body, - m_num_bodies); - return -1; - } - - idScalar size = BT_ID_MAX(level, 1); - const int body = m_current_body; - // length = 0.1 * size; - // with = 2 * 0.01 * size; - - /// these parameters are from the paper ... - /// TODO: add proper citation - m_parent[body] = parent; - m_mass[body] = 0.1 * BT_ID_POW(size, 3); - m_body_r_body_com[body](0) = 0.05 * size; - m_body_r_body_com[body](1) = 0; - m_body_r_body_com[body](2) = 0; - // initialization - for (int i = 0; i < 3; i++) { - m_parent_r_parent_body_ref[body](i) = 0; - for (int j = 0; j < 3; j++) { - m_body_I_body[body](i, j) = 0.0; - m_body_T_parent_ref[body](i, j) = 0.0; - } - } - const idScalar size_5 = pow(size, 5); - m_body_I_body[body](0, 0) = size_5 / 0.2e6; - m_body_I_body[body](1, 1) = size_5 * 403 / 1.2e6; - m_body_I_body[body](2, 2) = m_body_I_body[body](1, 1); - - getVecMatFromDH(0, 0, a_DH_in, alpha_DH_in, &m_parent_r_parent_body_ref[body], - &m_body_T_parent_ref[body]); - - // attach "level" Dill systems of levels 1...level - for (int i = 1; i <= level; i++) { - idScalar d_DH = 0.01 * size; - if (i == level) { - d_DH = 0.0; - } - const idScalar a_DH = i * 0.1; - const idScalar alpha_DH = i * BT_ID_PI / 3.0; - m_current_body++; - recurseDill(i - 1, body, d_DH, a_DH, alpha_DH); - } - - return 0; // ok! -} -} diff --git a/extern/bullet/src/Extras/InverseDynamics/DillCreator.hpp b/extern/bullet/src/Extras/InverseDynamics/DillCreator.hpp deleted file mode 100644 index fbe0e8e22786..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/DillCreator.hpp +++ /dev/null @@ -1,47 +0,0 @@ -#ifndef DILLCREATOR_HPP_ -#define DILLCREATOR_HPP_ - -#include "MultiBodyTreeCreator.hpp" - -namespace btInverseDynamics { - - -/// Creator class for building a "Dill" system as intruduced as benchmark example in -/// Featherstone (1999), "A Divide-and-Conquer Articulated-Body Algorithm for Parallel O(log(n)) -/// Calculation of Rigid-Body Dynamics. Part 2: Trees, Loops, and Accuracy.", The International -/// Journal of Robotics Research 18 (9): 876–892. doi : 10.1177 / 02783649922066628. -/// -/// This is a self-similar branched tree, somewhat resembling a dill plant -class DillCreator : public MultiBodyTreeCreator { -public: - /// ctor - /// @param levels the number of dill levels - DillCreator(int levels); - /// dtor - ~DillCreator(); - ///\copydoc MultiBodyTreeCreator::getNumBodies - int getNumBodies(int* num_bodies) const; - ///\copydoc MultiBodyTreeCreator::getBody - int getBody(const int body_index, int* parent_index, JointType* joint_type, - vec3* parent_r_parent_body_ref, mat33* body_T_parent_ref, vec3* body_axis_of_motion, - idScalar* mass, vec3* body_r_body_com, mat33* body_I_body, int* user_int, - void** user_ptr) const; - -private: - /// recursively generate dill bodies. - /// TODO better documentation - int recurseDill(const int levels, const int parent, const idScalar d_DH_in, - const idScalar a_DH_in, const idScalar alpha_DH_in); - int m_level; - int m_num_bodies; - idArray::type m_parent; - idArray::type m_parent_r_parent_body_ref; - idArray::type m_body_T_parent_ref; - idArray::type m_body_axis_of_motion; - idArray::type m_mass; - idArray::type m_body_r_body_com; - idArray::type m_body_I_body; - int m_current_body; -}; -} -#endif diff --git a/extern/bullet/src/Extras/InverseDynamics/IDRandomUtil.cpp b/extern/bullet/src/Extras/InverseDynamics/IDRandomUtil.cpp deleted file mode 100644 index fff352490491..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/IDRandomUtil.cpp +++ /dev/null @@ -1,71 +0,0 @@ -#include -#include -#include - -#include "BulletInverseDynamics/IDConfig.hpp" -#include "BulletInverseDynamics/IDMath.hpp" -#include "IDRandomUtil.hpp" - - -namespace btInverseDynamics { - -// constants for random mass and inertia generation -// these are arbitrary positive values. -static const float mass_min = 0.001; -static const float mass_max = 1.0; - -void randomInit() { srand(time(NULL)); } -void randomInit(unsigned seed) { srand(seed); } - -int randomInt(int low, int high) { return rand() % (high + 1 - low) + low; } - -float randomFloat(float low, float high) { - return low + static_cast(rand()) / RAND_MAX * (high - low); -} - -float randomMass() { return randomFloat(mass_min, mass_max); } - -vec3 randomInertiaPrincipal() { - vec3 inertia; - do { - inertia(0) = randomFloat(mass_min, mass_max); - inertia(1) = randomFloat(mass_min, mass_max); - inertia(2) = randomFloat(mass_min, mass_max); - } while (inertia(0) + inertia(1) < inertia(2) || inertia(0) + inertia(2) < inertia(1) || - inertia(1) + inertia(2) < inertia(0)); - return inertia; -} - -mat33 randomInertiaMatrix() { - // generate random valid inertia matrix by first getting valid components - // along major axes and then rotating by random amount - vec3 principal = randomInertiaPrincipal(); - mat33 rot(transformX(randomFloat(-BT_ID_PI, BT_ID_PI)) * transformY(randomFloat(-BT_ID_PI, BT_ID_PI)) * - transformZ(randomFloat(-BT_ID_PI, BT_ID_PI))); - mat33 inertia; - inertia(0, 0) = principal(0); - inertia(0, 1) = 0; - inertia(0, 2) = 0; - inertia(1, 0) = 0; - inertia(1, 1) = principal(1); - inertia(1, 2) = 0; - inertia(2, 0) = 0; - inertia(2, 1) = 0; - inertia(2, 2) = principal(2); - return rot * inertia * rot.transpose(); -} - -vec3 randomAxis() { - vec3 axis; - idScalar length; - do { - axis(0) = randomFloat(-1.0, 1.0); - axis(1) = randomFloat(-1.0, 1.0); - axis(2) = randomFloat(-1.0, 1.0); - - length = BT_ID_SQRT(BT_ID_POW(axis(0), 2) + BT_ID_POW(axis(1), 2) + BT_ID_POW(axis(2), 2)); - } while (length < 0.01); - - return axis / length; -} -} diff --git a/extern/bullet/src/Extras/InverseDynamics/IDRandomUtil.hpp b/extern/bullet/src/Extras/InverseDynamics/IDRandomUtil.hpp deleted file mode 100644 index 72a97fa2b131..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/IDRandomUtil.hpp +++ /dev/null @@ -1,36 +0,0 @@ -#ifndef ID_RANDOM_UTIL_HPP_ -#define ID_RANDOM_UTIL_HPP_ -#include "BulletInverseDynamics/IDConfig.hpp" -namespace btInverseDynamics { -/// seed random number generator using time() -void randomInit(); -/// seed random number generator with identical value to get repeatable results -void randomInit(unsigned seed); -/// Generate (not quite) uniformly distributed random integers in [low, high] -/// Note: this is a low-quality implementation using only rand(), as -/// C++11 is not supported in bullet. -/// The results will *not* be perfectly uniform. -/// \param low is the lower bound (inclusive) -/// \param high is the lower bound (inclusive) -/// \return a random number within [\param low, \param high] -int randomInt(int low, int high); -/// Generate a (not quite) uniformly distributed random floats in [low, high] -/// Note: this is a low-quality implementation using only rand(), as -/// C++11 is not supported in bullet. -/// The results will *not* be perfectly uniform. -/// \param low is the lower bound (inclusive) -/// \param high is the lower bound (inclusive) -/// \return a random number within [\param low, \param high] -float randomFloat(float low, float high); - -/// generate a random valid mass value -/// \returns random mass -float randomMass(); -/// generate a random valid vector of principal moments of inertia -vec3 randomInertiaPrincipal(); -/// generate a random valid moment of inertia matrix -mat33 randomInertiaMatrix(); -/// generate a random unit vector -vec3 randomAxis(); -} -#endif diff --git a/extern/bullet/src/Extras/InverseDynamics/MultiBodyNameMap.cpp b/extern/bullet/src/Extras/InverseDynamics/MultiBodyNameMap.cpp deleted file mode 100644 index 81d33f2855e7..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/MultiBodyNameMap.cpp +++ /dev/null @@ -1,78 +0,0 @@ -#include "MultiBodyNameMap.hpp" - -namespace btInverseDynamics { - -MultiBodyNameMap::MultiBodyNameMap() {} - -int MultiBodyNameMap::addBody(const int index, const std::string& name) { - if (m_index_to_body_name.count(index) > 0) { - bt_id_error_message("trying to add index %d again\n", index); - return -1; - } - if (m_body_name_to_index.count(name) > 0) { - bt_id_error_message("trying to add name %s again\n", name.c_str()); - return -1; - } - - m_index_to_body_name[index] = name; - m_body_name_to_index[name] = index; - - return 0; -} - -int MultiBodyNameMap::addJoint(const int index, const std::string& name) { - if (m_index_to_joint_name.count(index) > 0) { - bt_id_error_message("trying to add index %d again\n", index); - return -1; - } - if (m_joint_name_to_index.count(name) > 0) { - bt_id_error_message("trying to add name %s again\n", name.c_str()); - return -1; - } - - m_index_to_joint_name[index] = name; - m_joint_name_to_index[name] = index; - - return 0; -} - -int MultiBodyNameMap::getBodyName(const int index, std::string* name) const { - std::map::const_iterator it = m_index_to_body_name.find(index); - if (it == m_index_to_body_name.end()) { - bt_id_error_message("index %d not known\n", index); - return -1; - } - *name = it->second; - return 0; -} - -int MultiBodyNameMap::getJointName(const int index, std::string* name) const { - std::map::const_iterator it = m_index_to_joint_name.find(index); - if (it == m_index_to_joint_name.end()) { - bt_id_error_message("index %d not known\n", index); - return -1; - } - *name = it->second; - return 0; -} - -int MultiBodyNameMap::getBodyIndex(const std::string& name, int* index) const { - std::map::const_iterator it = m_body_name_to_index.find(name); - if (it == m_body_name_to_index.end()) { - bt_id_error_message("name %s not known\n", name.c_str()); - return -1; - } - *index = it->second; - return 0; -} - -int MultiBodyNameMap::getJointIndex(const std::string& name, int* index) const { - std::map::const_iterator it = m_joint_name_to_index.find(name); - if (it == m_joint_name_to_index.end()) { - bt_id_error_message("name %s not known\n", name.c_str()); - return -1; - } - *index = it->second; - return 0; -} -} diff --git a/extern/bullet/src/Extras/InverseDynamics/MultiBodyNameMap.hpp b/extern/bullet/src/Extras/InverseDynamics/MultiBodyNameMap.hpp deleted file mode 100644 index a5e024ce044b..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/MultiBodyNameMap.hpp +++ /dev/null @@ -1,54 +0,0 @@ -#ifndef MULTIBODYNAMEMAP_HPP_ -#define MULTIBODYNAMEMAP_HPP_ - -#include "BulletInverseDynamics/IDConfig.hpp" -#include -#include - -namespace btInverseDynamics { - -/// \brief The MultiBodyNameMap class -/// Utility class that stores a maps from body/joint indices to/from body and joint names -class MultiBodyNameMap { -public: - MultiBodyNameMap(); - /// add a body to the map - /// @param index of the body - /// @param name name of the body - /// @return 0 on success, -1 on failure - int addBody(const int index, const std::string& name); - /// add a joint to the map - /// @param index of the joint - /// @param name name of the joint - /// @return 0 on success, -1 on failure - int addJoint(const int index, const std::string& name); - /// get body name from index - /// @param index of the body - /// @param body_name name of the body - /// @return 0 on success, -1 on failure - int getBodyName(const int index, std::string* name) const; - /// get joint name from index - /// @param index of the joint - /// @param joint_name name of the joint - /// @return 0 on success, -1 on failure - int getJointName(const int index, std::string* name) const; - /// get body index from name - /// @param index of the body - /// @param name name of the body - /// @return 0 on success, -1 on failure - int getBodyIndex(const std::string& name, int* index) const; - /// get joint index from name - /// @param index of the joint - /// @param name name of the joint - /// @return 0 on success, -1 on failure - int getJointIndex(const std::string& name, int* index) const; - -private: - std::map m_index_to_joint_name; - std::map m_index_to_body_name; - - std::map m_joint_name_to_index; - std::map m_body_name_to_index; -}; -} -#endif // MULTIBODYNAMEMAP_HPP_ diff --git a/extern/bullet/src/Extras/InverseDynamics/MultiBodyTreeCreator.cpp b/extern/bullet/src/Extras/InverseDynamics/MultiBodyTreeCreator.cpp deleted file mode 100644 index 0972f4396aad..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/MultiBodyTreeCreator.cpp +++ /dev/null @@ -1,64 +0,0 @@ -#include "MultiBodyTreeCreator.hpp" - -namespace btInverseDynamics { - -MultiBodyTree* CreateMultiBodyTree(const MultiBodyTreeCreator& creator) { - int num_bodies; - int parent_index; - JointType joint_type; - vec3 body_r_parent_body_ref; - mat33 body_R_parent_ref; - vec3 body_axis_of_motion; - idScalar mass; - vec3 body_r_body_com; - mat33 body_I_body; - int user_int; - void* user_ptr; - - MultiBodyTree* tree = new MultiBodyTree(); - if (0x0 == tree) { - bt_id_error_message("cannot allocate tree\n"); - return 0x0; - } - - // TODO: move to some policy argument - tree->setAcceptInvalidMassParameters(false); - - // get number of bodies in the system - if (-1 == creator.getNumBodies(&num_bodies)) { - bt_id_error_message("getting body indices\n"); - delete tree; - return 0x0; - } - - // get data for all bodies - for (int index = 0; index < num_bodies; index++) { - // get body parameters from user callbacks - if (-1 == - creator.getBody(index, &parent_index, &joint_type, &body_r_parent_body_ref, - &body_R_parent_ref, &body_axis_of_motion, &mass, &body_r_body_com, - &body_I_body, &user_int, &user_ptr)) { - bt_id_error_message("getting data for body %d\n", index); - delete tree; - return 0x0; - } - // add body to system - if (-1 == - tree->addBody(index, parent_index, joint_type, body_r_parent_body_ref, - body_R_parent_ref, body_axis_of_motion, mass, body_r_body_com, - body_I_body, user_int, user_ptr)) { - bt_id_error_message("adding body %d\n", index); - delete tree; - return 0x0; - } - } - // finalize initialization - if (-1 == tree->finalize()) { - bt_id_error_message("building system\n"); - delete tree; - return 0x0; - } - - return tree; -} -} diff --git a/extern/bullet/src/Extras/InverseDynamics/MultiBodyTreeCreator.hpp b/extern/bullet/src/Extras/InverseDynamics/MultiBodyTreeCreator.hpp deleted file mode 100644 index bbf552eb6d05..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/MultiBodyTreeCreator.hpp +++ /dev/null @@ -1,45 +0,0 @@ -#ifndef MULTI_BODY_TREE_CREATOR_HPP_ -#define MULTI_BODY_TREE_CREATOR_HPP_ - -#include -#include -#include "BulletInverseDynamics/IDConfig.hpp" -#include "BulletInverseDynamics/IDMath.hpp" -#include "BulletInverseDynamics/MultiBodyTree.hpp" -#include "MultiBodyNameMap.hpp" - -namespace btInverseDynamics { -/// Interface class for initializing a MultiBodyTree instance. -/// Data to be provided is modeled on the URDF specification. -/// The user can derive from this class in order to programmatically -/// initialize a system. -class MultiBodyTreeCreator { -public: - /// the dtor - virtual ~MultiBodyTreeCreator() {} - /// Get the number of bodies in the system - /// @param num_bodies write number of bodies here - /// @return 0 on success, -1 on error - virtual int getNumBodies(int* num_bodies) const = 0; - /// Interface for accessing link mass properties. - /// For detailed description of data, @sa MultiBodyTree::addBody - /// \copydoc MultiBodyTree::addBody - virtual int getBody(const int body_index, int* parent_index, JointType* joint_type, - vec3* parent_r_parent_body_ref, mat33* body_T_parent_ref, - vec3* body_axis_of_motion, idScalar* mass, vec3* body_r_body_com, - mat33* body_I_body, int* user_int, void** user_ptr) const = 0; - /// @return a pointer to a name mapping utility class, or 0x0 if not available - virtual const MultiBodyNameMap* getNameMap() const {return 0x0;} -}; - -/// Create a multibody object. -/// @param creator an object implementing the MultiBodyTreeCreator interface -/// that returns data defining the system -/// @return A pointer to an allocated multibodytree instance, or -/// 0x0 if an error occured. -MultiBodyTree* CreateMultiBodyTree(const MultiBodyTreeCreator& creator); -} - -// does urdf have gravity direction ?? - -#endif // MULTI_BODY_TREE_CREATOR_HPP_ diff --git a/extern/bullet/src/Extras/InverseDynamics/MultiBodyTreeDebugGraph.cpp b/extern/bullet/src/Extras/InverseDynamics/MultiBodyTreeDebugGraph.cpp deleted file mode 100644 index aac58e4b32ba..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/MultiBodyTreeDebugGraph.cpp +++ /dev/null @@ -1,64 +0,0 @@ -#include "MultiBodyTreeDebugGraph.hpp" - -#include - -namespace btInverseDynamics { - -int writeGraphvizDotFile(const MultiBodyTree* tree, const MultiBodyNameMap* map, - const char* filename) { - if (0x0 == tree) { - bt_id_error_message("tree pointer is null\n"); - return -1; - } - if (0x0 == filename) { - bt_id_error_message("filename is null\n"); - return -1; - } - - FILE* fp = fopen(filename, "w"); - if (NULL == fp) { - bt_id_error_message("cannot open file %s for writing\n", filename); - return -1; - } - fprintf(fp, "// to generate postscript file, run dot -Tps %s -o %s.ps\n" - "// details see graphviz documentation at http://graphviz.org\n" - "digraph tree {\n", - filename, filename); - - for (int body = 0; body < tree->numBodies(); body++) { - std::string name; - if (0x0 != map) { - if (-1 == map->getBodyName(body, &name)) { - bt_id_error_message("can't get name of body %d\n", body); - return -1; - } - fprintf(fp, " %d [label=\"%d/%s\"];\n", body, body, name.c_str()); - } - } - for (int body = 0; body < tree->numBodies(); body++) { - int parent; - const char* joint_type; - int qi; - if (-1 == tree->getParentIndex(body, &parent)) { - bt_id_error_message("indexing error\n"); - return -1; - } - if (-1 == tree->getJointTypeStr(body, &joint_type)) { - bt_id_error_message("indexing error\n"); - return -1; - } - if (-1 == tree->getDoFOffset(body, &qi)) { - bt_id_error_message("indexing error\n"); - return -1; - } - if (-1 != parent) { - fprintf(fp, " %d -> %d [label= \"type:%s, q=%d\"];\n", parent, body, - joint_type, qi); - } - } - - fprintf(fp, "}\n"); - fclose(fp); - return 0; -} -} diff --git a/extern/bullet/src/Extras/InverseDynamics/MultiBodyTreeDebugGraph.hpp b/extern/bullet/src/Extras/InverseDynamics/MultiBodyTreeDebugGraph.hpp deleted file mode 100644 index f249d09527e9..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/MultiBodyTreeDebugGraph.hpp +++ /dev/null @@ -1,17 +0,0 @@ -#ifndef MULTIBODYTREEDEBUGGRAPH_HPP_ -#define MULTIBODYTREEDEBUGGRAPH_HPP_ -#include "BulletInverseDynamics/IDConfig.hpp" -#include "BulletInverseDynamics/MultiBodyTree.hpp" -#include "MultiBodyNameMap.hpp" - -namespace btInverseDynamics { -/// generate a dot-file of the multibody tree for generating a graph using graphviz' dot tool -/// @param tree the multibody tree -/// @param map to add names of links (if 0x0, no names will be added) -/// @param filename name for the output file -/// @return 0 on success, -1 on error -int writeGraphvizDotFile(const MultiBodyTree* tree, const MultiBodyNameMap* map, - const char* filename); -} - -#endif // MULTIBODYTREEDEBUGGRAPH_HPP diff --git a/extern/bullet/src/Extras/InverseDynamics/RandomTreeCreator.cpp b/extern/bullet/src/Extras/InverseDynamics/RandomTreeCreator.cpp deleted file mode 100644 index a531037a2d49..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/RandomTreeCreator.cpp +++ /dev/null @@ -1,81 +0,0 @@ -#include "RandomTreeCreator.hpp" - -#include - -#include "IDRandomUtil.hpp" - -namespace btInverseDynamics { - -RandomTreeCreator::RandomTreeCreator(const int max_bodies, bool random_seed) { - // seed generator - if(random_seed) { - randomInit(); // seeds with time() - } else { - randomInit(1); // seeds with 1 - } - m_num_bodies = randomInt(1, max_bodies); -} - -RandomTreeCreator::~RandomTreeCreator() {} - -int RandomTreeCreator::getNumBodies(int* num_bodies) const { - *num_bodies = m_num_bodies; - return 0; -} - -int RandomTreeCreator::getBody(const int body_index, int* parent_index, JointType* joint_type, - vec3* parent_r_parent_body_ref, mat33* body_T_parent_ref, - vec3* body_axis_of_motion, idScalar* mass, vec3* body_r_body_com, - mat33* body_I_body, int* user_int, void** user_ptr) const { - if(0 == body_index) { //root body - *parent_index = -1; - } else { - *parent_index = randomInt(0, body_index - 1); - } - - switch (randomInt(0, 3)) { - case 0: - *joint_type = FIXED; - break; - case 1: - *joint_type = REVOLUTE; - break; - case 2: - *joint_type = PRISMATIC; - break; - case 3: - *joint_type = FLOATING; - break; - default: - bt_id_error_message("randomInt() result out of range\n"); - return -1; - } - - (*parent_r_parent_body_ref)(0) = randomFloat(-1.0, 1.0); - (*parent_r_parent_body_ref)(1) = randomFloat(-1.0, 1.0); - (*parent_r_parent_body_ref)(2) = randomFloat(-1.0, 1.0); - - bodyTParentFromAxisAngle(randomAxis(), randomFloat(-BT_ID_PI, BT_ID_PI), body_T_parent_ref); - - *body_axis_of_motion = randomAxis(); - *mass = randomMass(); - (*body_r_body_com)(0) = randomFloat(-1.0, 1.0); - (*body_r_body_com)(1) = randomFloat(-1.0, 1.0); - (*body_r_body_com)(2) = randomFloat(-1.0, 1.0); - const double a = randomFloat(-BT_ID_PI, BT_ID_PI); - const double b = randomFloat(-BT_ID_PI, BT_ID_PI); - const double c = randomFloat(-BT_ID_PI, BT_ID_PI); - vec3 ii = randomInertiaPrincipal(); - mat33 ii_diag; - setZero(ii_diag); - ii_diag(0,0)=ii(0); - ii_diag(1,1)=ii(1); - ii_diag(2,2)=ii(2); - *body_I_body = transformX(a) * transformY(b) * transformZ(c) * ii_diag * - transformZ(-c) * transformY(-b) * transformX(-a); - *user_int = 0; - *user_ptr = 0; - - return 0; -} -} diff --git a/extern/bullet/src/Extras/InverseDynamics/RandomTreeCreator.hpp b/extern/bullet/src/Extras/InverseDynamics/RandomTreeCreator.hpp deleted file mode 100644 index bbadb997d23e..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/RandomTreeCreator.hpp +++ /dev/null @@ -1,31 +0,0 @@ -#ifndef RANDOMTREE_CREATOR_HPP_ -#define RANDOMTREE_CREATOR_HPP_ - -#include "BulletInverseDynamics/IDConfig.hpp" -#include "MultiBodyTreeCreator.hpp" - -namespace btInverseDynamics { -/// Generate a random MultiBodyTree with fixed or floating base and fixed, prismatic or revolute -/// joints -/// Uses a pseudo random number generator seeded from a random device. -class RandomTreeCreator : public MultiBodyTreeCreator { -public: - /// ctor - /// @param max_bodies maximum number of bodies - /// @param gravity gravitational acceleration - /// @param use_seed if true, seed random number generator - RandomTreeCreator(const int max_bodies, bool use_seed=false); - ~RandomTreeCreator(); - ///\copydoc MultiBodyTreeCreator::getNumBodies - int getNumBodies(int* num_bodies) const; - ///\copydoc MultiBodyTreeCreator::getBody - int getBody(const int body_index, int* parent_index, JointType* joint_type, - vec3* parent_r_parent_body_ref, mat33* body_T_parent_ref, vec3* body_axis_of_motion, - idScalar* mass, vec3* body_r_body_com, mat33* body_I_body, int* user_int, - void** user_ptr) const; - -private: - int m_num_bodies; -}; -} -#endif // RANDOMTREE_CREATOR_HPP_ diff --git a/extern/bullet/src/Extras/InverseDynamics/SimpleTreeCreator.cpp b/extern/bullet/src/Extras/InverseDynamics/SimpleTreeCreator.cpp deleted file mode 100644 index e2b308ebe000..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/SimpleTreeCreator.cpp +++ /dev/null @@ -1,69 +0,0 @@ -#include "SimpleTreeCreator.hpp" - -#include - -namespace btInverseDynamics { -/// minimal "tree" (chain) -SimpleTreeCreator::SimpleTreeCreator(int dim) : m_num_bodies(dim) { - m_mass = 1.0; - m_body_T_parent_ref(0, 0) = 1; - m_body_T_parent_ref(0, 1) = 0; - m_body_T_parent_ref(0, 2) = 0; - m_body_T_parent_ref(1, 0) = 0; - m_body_T_parent_ref(1, 1) = 1; - m_body_T_parent_ref(1, 2) = 0; - m_body_T_parent_ref(2, 0) = 0; - m_body_T_parent_ref(2, 1) = 0; - m_body_T_parent_ref(2, 2) = 1; - - m_parent_r_parent_body_ref(0) = 1.0; - m_parent_r_parent_body_ref(1) = 0.0; - m_parent_r_parent_body_ref(2) = 0.0; - - m_body_r_body_com(0) = 0.5; - m_body_r_body_com(1) = 0.0; - m_body_r_body_com(2) = 0.0; - - m_body_I_body(0, 0) = 1; - m_body_I_body(0, 1) = 0; - m_body_I_body(0, 2) = 0; - m_body_I_body(1, 0) = 0; - m_body_I_body(1, 1) = 1; - m_body_I_body(1, 2) = 0; - m_body_I_body(2, 0) = 0; - m_body_I_body(2, 1) = 0; - m_body_I_body(2, 2) = 1; - - m_axis(0) = 0; - m_axis(1) = 0; - m_axis(2) = 1; -} -int SimpleTreeCreator::getNumBodies(int* num_bodies) const { - *num_bodies = m_num_bodies; - return 0; -} - -int SimpleTreeCreator::getBody(const int body_index, int* parent_index, JointType* joint_type, - vec3* parent_r_parent_body_ref, mat33* body_T_parent_ref, - vec3* body_axis_of_motion, idScalar* mass, vec3* body_r_body_com, - mat33* body_I_body, int* user_int, void** user_ptr) const { - *parent_index = body_index - 1; - if (body_index % 2) { - *joint_type = PRISMATIC; - } else { - *joint_type = REVOLUTE; - } - *parent_r_parent_body_ref = m_parent_r_parent_body_ref; - if (0 == body_index) { - (*parent_r_parent_body_ref)(2) = 1.0; - } - *body_T_parent_ref = m_body_T_parent_ref; - *body_axis_of_motion = m_axis; - *mass = m_mass; - *body_r_body_com = m_body_r_body_com; - *body_I_body = m_body_I_body; - *user_int = 0; - *user_ptr = 0; - return 0; -} -} diff --git a/extern/bullet/src/Extras/InverseDynamics/SimpleTreeCreator.hpp b/extern/bullet/src/Extras/InverseDynamics/SimpleTreeCreator.hpp deleted file mode 100644 index f336eae7219f..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/SimpleTreeCreator.hpp +++ /dev/null @@ -1,34 +0,0 @@ -#ifndef SIMPLETREECREATOR_HPP_ -#define SIMPLETREECREATOR_HPP_ - -#include "MultiBodyTreeCreator.hpp" - -namespace btInverseDynamics { - -/// minimal "tree" (chain) -class SimpleTreeCreator : public MultiBodyTreeCreator { -public: - /// ctor - /// @param dim number of bodies - SimpleTreeCreator(int dim); - // dtor - ~SimpleTreeCreator() {} - ///\copydoc MultiBodyTreeCreator::getNumBodies - int getNumBodies(int* num_bodies) const; - ///\copydoc MultiBodyTreeCreator::getBody - int getBody(const int body_index, int* parent_index, JointType* joint_type, - vec3* parent_r_parent_body_ref, mat33* body_T_parent_ref, vec3* body_axis_of_motion, - idScalar* mass, vec3* body_r_body_com, mat33* body_I_body, int* user_int, - void** user_ptr) const; - -private: - int m_num_bodies; - idScalar m_mass; - mat33 m_body_T_parent_ref; - vec3 m_parent_r_parent_body_ref; - vec3 m_body_r_body_com; - mat33 m_body_I_body; - vec3 m_axis; -}; -} -#endif // SIMPLETREECREATOR_HPP_ diff --git a/extern/bullet/src/Extras/InverseDynamics/User2InternalIndex.cpp b/extern/bullet/src/Extras/InverseDynamics/User2InternalIndex.cpp deleted file mode 100644 index 76874bf707ff..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/User2InternalIndex.cpp +++ /dev/null @@ -1,99 +0,0 @@ -#include "User2InternalIndex.hpp" - -namespace btInverseDynamics { -User2InternalIndex::User2InternalIndex() : m_map_built(false) {} - -void User2InternalIndex::addBody(const int body, const int parent) { - m_user_parent_index_map[body] = parent; -} - -int User2InternalIndex::findRoot(int index) { - if (0 == m_user_parent_index_map.count(index)) { - return index; - } - return findRoot(m_user_parent_index_map[index]); -} - -// modelled after URDF2Bullet.cpp:void ComputeParentIndices(const -// URDFImporterInterface& u2b, URDF2BulletCachedData& cache, int urdfLinkIndex, -// int urdfParentIndex) -void User2InternalIndex::recurseIndexSets(const int user_body_index) { - m_user_to_internal[user_body_index] = m_current_index; - m_current_index++; - for (size_t i = 0; i < m_user_child_indices[user_body_index].size(); i++) { - recurseIndexSets(m_user_child_indices[user_body_index][i]); - } -} - -int User2InternalIndex::buildMapping() { - // find root index - int user_root_index = -1; - for (std::map::iterator it = m_user_parent_index_map.begin(); - it != m_user_parent_index_map.end(); it++) { - int current_root_index = findRoot(it->second); - if (it == m_user_parent_index_map.begin()) { - user_root_index = current_root_index; - } else { - if (user_root_index != current_root_index) { - bt_id_error_message("multiple roots (at least) %d and %d\n", user_root_index, - current_root_index); - return -1; - } - } - } - - // build child index map - for (std::map::iterator it = m_user_parent_index_map.begin(); - it != m_user_parent_index_map.end(); it++) { - m_user_child_indices[it->second].push_back(it->first); - } - - m_current_index = -1; - // build internal index set - m_user_to_internal[user_root_index] = -1; // add map for root link - recurseIndexSets(user_root_index); - - // reverse mapping - for (std::map::iterator it = m_user_to_internal.begin(); - it != m_user_to_internal.end(); it++) { - m_internal_to_user[it->second] = it->first; - } - - m_map_built = true; - return 0; -} - -int User2InternalIndex::user2internal(const int user, int *internal) const { - - if (!m_map_built) { - return -1; - } - - std::map::const_iterator it; - it = m_user_to_internal.find(user); - if (it != m_user_to_internal.end()) { - *internal = it->second; - return 0; - } else { - bt_id_error_message("no user index %d\n", user); - return -1; - } -} - -int User2InternalIndex::internal2user(const int internal, int *user) const { - - if (!m_map_built) { - return -1; - } - - std::map::const_iterator it; - it = m_internal_to_user.find(internal); - if (it != m_internal_to_user.end()) { - *user = it->second; - return 0; - } else { - bt_id_error_message("no internal index %d\n", internal); - return -1; - } -} -} diff --git a/extern/bullet/src/Extras/InverseDynamics/User2InternalIndex.hpp b/extern/bullet/src/Extras/InverseDynamics/User2InternalIndex.hpp deleted file mode 100644 index 06c7ef2aac19..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/User2InternalIndex.hpp +++ /dev/null @@ -1,46 +0,0 @@ -#ifndef USER2INTERNALINDEX_HPP -#define USER2INTERNALINDEX_HPP -#include -#include - -#include "BulletInverseDynamics/IDConfig.hpp" - -namespace btInverseDynamics { - -/// Convert arbitrary indexing scheme to internal indexing -/// used for MultiBodyTree -class User2InternalIndex { -public: - /// Ctor - User2InternalIndex(); - /// add body to index maps - /// @param body index of body to add (external) - /// @param parent index of parent body (external) - void addBody(const int body, const int parent); - /// build mapping from external to internal indexing - /// @return 0 on success, -1 on failure - int buildMapping(); - /// get internal index from external index - /// @param user external (user) index - /// @param internal pointer for storage of corresponding internal index - /// @return 0 on success, -1 on failure - int user2internal(const int user, int *internal) const; - /// get internal index from external index - /// @param user external (user) index - /// @param internal pointer for storage of corresponding internal index - /// @return 0 on success, -1 on failure - int internal2user(const int internal, int *user) const; - -private: - int findRoot(int index); - void recurseIndexSets(const int user_body_index); - bool m_map_built; - std::map m_user_parent_index_map; - std::map m_user_to_internal; - std::map m_internal_to_user; - std::map > m_user_child_indices; - int m_current_index; -}; -} - -#endif // USER2INTERNALINDEX_HPP diff --git a/extern/bullet/src/Extras/InverseDynamics/btMultiBodyFromURDF.hpp b/extern/bullet/src/Extras/InverseDynamics/btMultiBodyFromURDF.hpp deleted file mode 100644 index 444a7134e065..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/btMultiBodyFromURDF.hpp +++ /dev/null @@ -1,91 +0,0 @@ -#ifndef BTMULTIBODYFROMURDF_HPP -#define BTMULTIBODYFROMURDF_HPP - -#include "btBulletDynamicsCommon.h" -#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" -#include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h" -#include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h" -#include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h" -#include "../../examples/CommonInterfaces/CommonGUIHelperInterface.h" -#include "../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.h" -#include "../../examples/Importers/ImportURDFDemo/URDF2Bullet.h" -#include "../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.h" -#include "../../examples/Importers/ImportURDFDemo/URDF2Bullet.h" - -/// Create a btMultiBody model from URDF. -/// This is adapted from Bullet URDF loader example -class MyBtMultiBodyFromURDF { -public: - /// ctor - /// @param gravity gravitational acceleration (in world frame) - /// @param base_fixed if true, the root body is treated as fixed, - /// if false, it is treated as floating - MyBtMultiBodyFromURDF(const btVector3 &gravity, const bool base_fixed) - : m_gravity(gravity), m_base_fixed(base_fixed) { - m_broadphase = 0x0; - m_dispatcher = 0x0; - m_solver = 0x0; - m_collisionConfiguration = 0x0; - m_dynamicsWorld = 0x0; - m_multibody = 0x0; - } - /// dtor - ~MyBtMultiBodyFromURDF() { - delete m_dynamicsWorld; - delete m_solver; - delete m_broadphase; - delete m_dispatcher; - delete m_collisionConfiguration; - delete m_multibody; - } - /// @param name path to urdf file - void setFileName(const std::string name) { m_filename = name; } - /// load urdf file and build btMultiBody model - void init() { - this->createEmptyDynamicsWorld(); - m_dynamicsWorld->setGravity(m_gravity); - BulletURDFImporter urdf_importer(&m_nogfx,0,1,0); - URDFImporterInterface &u2b(urdf_importer); - bool loadOk = u2b.loadURDF(m_filename.c_str(), m_base_fixed); - - if (loadOk) { - btTransform identityTrans; - identityTrans.setIdentity(); - MyMultiBodyCreator creation(&m_nogfx); - const bool use_multibody = true; - ConvertURDF2Bullet(u2b, creation, identityTrans, m_dynamicsWorld, use_multibody, - u2b.getPathPrefix()); - m_multibody = creation.getBulletMultiBody(); - m_dynamicsWorld->stepSimulation(1. / 240., 0); - } - } - /// @return pointer to the btMultiBody model - btMultiBody *getBtMultiBody() { return m_multibody; } - -private: - // internal utility function - void createEmptyDynamicsWorld() { - m_collisionConfiguration = new btDefaultCollisionConfiguration(); - - /// use the default collision dispatcher. For parallel processing you can use a diffent - /// dispatcher (see Extras/BulletMultiThreaded) - m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration); - m_broadphase = new btDbvtBroadphase(); - m_solver = new btMultiBodyConstraintSolver; - m_dynamicsWorld = new btMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, m_solver, - m_collisionConfiguration); - m_dynamicsWorld->setGravity(m_gravity); - } - - btBroadphaseInterface *m_broadphase; - btCollisionDispatcher *m_dispatcher; - btMultiBodyConstraintSolver *m_solver; - btDefaultCollisionConfiguration *m_collisionConfiguration; - btMultiBodyDynamicsWorld *m_dynamicsWorld; - std::string m_filename; - DummyGUIHelper m_nogfx; - btMultiBody *m_multibody; - const btVector3 m_gravity; - const bool m_base_fixed; -}; -#endif // BTMULTIBODYFROMURDF_HPP diff --git a/extern/bullet/src/Extras/InverseDynamics/btMultiBodyTreeCreator.cpp b/extern/bullet/src/Extras/InverseDynamics/btMultiBodyTreeCreator.cpp deleted file mode 100644 index 1b32df61710f..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/btMultiBodyTreeCreator.cpp +++ /dev/null @@ -1,272 +0,0 @@ -#include "btMultiBodyTreeCreator.hpp" - -namespace btInverseDynamics { - -btMultiBodyTreeCreator::btMultiBodyTreeCreator() : m_initialized(false) {} - -int btMultiBodyTreeCreator::createFromBtMultiBody(const btMultiBody *btmb, const bool verbose) { - if (0x0 == btmb) { - bt_id_error_message("cannot create MultiBodyTree from null pointer\n"); - return -1; - } - - // in case this is a second call, discard old data - m_data.clear(); - m_initialized = false; - - // btMultiBody treats base link separately - m_data.resize(1 + btmb->getNumLinks()); - - // add base link data - { - LinkData &link = m_data[0]; - - link.parent_index = -1; - if (btmb->hasFixedBase()) { - link.joint_type = FIXED; - } else { - link.joint_type = FLOATING; - } - btTransform transform=(btmb->getBaseWorldTransform()); - //compute inverse dynamics in body-fixed frame - transform.setIdentity(); - - link.parent_r_parent_body_ref(0) = transform.getOrigin()[0]; - link.parent_r_parent_body_ref(1) = transform.getOrigin()[1]; - link.parent_r_parent_body_ref(2) = transform.getOrigin()[2]; - - link.body_T_parent_ref(0, 0) = transform.getBasis()[0][0]; - link.body_T_parent_ref(0, 1) = transform.getBasis()[0][1]; - link.body_T_parent_ref(0, 2) = transform.getBasis()[0][2]; - - link.body_T_parent_ref(1, 0) = transform.getBasis()[1][0]; - link.body_T_parent_ref(1, 1) = transform.getBasis()[1][1]; - link.body_T_parent_ref(1, 2) = transform.getBasis()[1][2]; - - link.body_T_parent_ref(2, 0) = transform.getBasis()[2][0]; - link.body_T_parent_ref(2, 1) = transform.getBasis()[2][1]; - link.body_T_parent_ref(2, 2) = transform.getBasis()[2][2]; - - // random unit vector. value not used for fixed or floating joints. - link.body_axis_of_motion(0) = 0; - link.body_axis_of_motion(1) = 0; - link.body_axis_of_motion(2) = 1; - - link.mass = btmb->getBaseMass(); - // link frame in the center of mass - link.body_r_body_com(0) = 0; - link.body_r_body_com(1) = 0; - link.body_r_body_com(2) = 0; - // BulletDynamics uses body-fixed frame in the cog, aligned with principal axes - link.body_I_body(0, 0) = btmb->getBaseInertia()[0]; - link.body_I_body(0, 1) = 0.0; - link.body_I_body(0, 2) = 0.0; - link.body_I_body(1, 0) = 0.0; - link.body_I_body(1, 1) = btmb->getBaseInertia()[1]; - link.body_I_body(1, 2) = 0.0; - link.body_I_body(2, 0) = 0.0; - link.body_I_body(2, 1) = 0.0; - link.body_I_body(2, 2) = btmb->getBaseInertia()[2]; - // shift reference point to link origin (in joint axis) - mat33 tilde_r_com = tildeOperator(link.body_r_body_com); - link.body_I_body = link.body_I_body - link.mass * tilde_r_com * tilde_r_com; - if (verbose) { - id_printf("base: mass= %f, bt_inertia= [%f %f %f]\n" - "Io= [%f %f %f;\n" - " %f %f %f;\n" - " %f %f %f]\n", - link.mass, btmb->getBaseInertia()[0], btmb->getBaseInertia()[1], - btmb->getBaseInertia()[2], link.body_I_body(0, 0), link.body_I_body(0, 1), - link.body_I_body(0, 2), link.body_I_body(1, 0), link.body_I_body(1, 1), - link.body_I_body(1, 2), link.body_I_body(2, 0), link.body_I_body(2, 1), - link.body_I_body(2, 2)); - } - } - - for (int bt_index = 0; bt_index < btmb->getNumLinks(); bt_index++) { - if (verbose) { - id_printf("bt->id: converting link %d\n", bt_index); - } - const btMultibodyLink &bt_link = btmb->getLink(bt_index); - LinkData &link = m_data[bt_index + 1]; - - link.parent_index = bt_link.m_parent + 1; - - link.mass = bt_link.m_mass; - if (verbose) { - id_printf("mass= %f\n", link.mass); - } - // from this body's pivot to this body's com in this body's frame - link.body_r_body_com[0] = bt_link.m_dVector[0]; - link.body_r_body_com[1] = bt_link.m_dVector[1]; - link.body_r_body_com[2] = bt_link.m_dVector[2]; - if (verbose) { - id_printf("com= %f %f %f\n", link.body_r_body_com[0], link.body_r_body_com[1], - link.body_r_body_com[2]); - } - // BulletDynamics uses a body-fixed frame in the CoM, aligned with principal axes - link.body_I_body(0, 0) = bt_link.m_inertiaLocal[0]; - link.body_I_body(0, 1) = 0.0; - link.body_I_body(0, 2) = 0.0; - link.body_I_body(1, 0) = 0.0; - link.body_I_body(1, 1) = bt_link.m_inertiaLocal[1]; - link.body_I_body(1, 2) = 0.0; - link.body_I_body(2, 0) = 0.0; - link.body_I_body(2, 1) = 0.0; - link.body_I_body(2, 2) = bt_link.m_inertiaLocal[2]; - // shift reference point to link origin (in joint axis) - mat33 tilde_r_com = tildeOperator(link.body_r_body_com); - link.body_I_body = link.body_I_body - link.mass * tilde_r_com * tilde_r_com; - - if (verbose) { - id_printf("link %d: mass= %f, bt_inertia= [%f %f %f]\n" - "Io= [%f %f %f;\n" - " %f %f %f;\n" - " %f %f %f]\n", - bt_index, link.mass, bt_link.m_inertiaLocal[0], bt_link.m_inertiaLocal[1], - bt_link.m_inertiaLocal[2], link.body_I_body(0, 0), link.body_I_body(0, 1), - link.body_I_body(0, 2), link.body_I_body(1, 0), link.body_I_body(1, 1), - link.body_I_body(1, 2), link.body_I_body(2, 0), link.body_I_body(2, 1), - link.body_I_body(2, 2)); - } - // transform for vectors written in parent frame to this link's body-fixed frame - btMatrix3x3 basis = btTransform(bt_link.m_zeroRotParentToThis).getBasis(); - link.body_T_parent_ref(0, 0) = basis[0][0]; - link.body_T_parent_ref(0, 1) = basis[0][1]; - link.body_T_parent_ref(0, 2) = basis[0][2]; - link.body_T_parent_ref(1, 0) = basis[1][0]; - link.body_T_parent_ref(1, 1) = basis[1][1]; - link.body_T_parent_ref(1, 2) = basis[1][2]; - link.body_T_parent_ref(2, 0) = basis[2][0]; - link.body_T_parent_ref(2, 1) = basis[2][1]; - link.body_T_parent_ref(2, 2) = basis[2][2]; - if (verbose) { - id_printf("body_T_parent_ref= %f %f %f\n" - " %f %f %f\n" - " %f %f %f\n", - basis[0][0], basis[0][1], basis[0][2], basis[1][0], basis[1][1], basis[1][2], - basis[2][0], basis[2][1], basis[2][2]); - } - switch (bt_link.m_jointType) { - case btMultibodyLink::eRevolute: - link.joint_type = REVOLUTE; - if (verbose) { - id_printf("type= revolute\n"); - } - link.body_axis_of_motion(0) = bt_link.m_axes[0].m_topVec[0]; - link.body_axis_of_motion(1) = bt_link.m_axes[0].m_topVec[1]; - link.body_axis_of_motion(2) = bt_link.m_axes[0].m_topVec[2]; - - // for revolute joints, m_eVector = parentComToThisPivotOffset - // m_dVector = thisPivotToThisComOffset - // from parent com to pivot, in parent frame - link.parent_r_parent_body_ref(0) = bt_link.m_eVector[0]; - link.parent_r_parent_body_ref(1) = bt_link.m_eVector[1]; - link.parent_r_parent_body_ref(2) = bt_link.m_eVector[2]; - break; - case btMultibodyLink::ePrismatic: - link.joint_type = PRISMATIC; - if (verbose) { - id_printf("type= prismatic\n"); - } - link.body_axis_of_motion(0) = bt_link.m_axes[0].m_bottomVec[0]; - link.body_axis_of_motion(1) = bt_link.m_axes[0].m_bottomVec[1]; - link.body_axis_of_motion(2) = bt_link.m_axes[0].m_bottomVec[2]; - - // for prismatic joints, eVector - // according to documentation : - // parentComToThisComOffset - // but seems to be: from parent's com to parent's - // pivot ?? - // m_dVector = thisPivotToThisComOffset - link.parent_r_parent_body_ref(0) = bt_link.m_eVector[0]; - link.parent_r_parent_body_ref(1) = bt_link.m_eVector[1]; - link.parent_r_parent_body_ref(2) = bt_link.m_eVector[2]; - break; - case btMultibodyLink::eSpherical: - bt_id_error_message("spherical joints not implemented\n"); - return -1; - case btMultibodyLink::ePlanar: - bt_id_error_message("planar joints not implemented\n"); - return -1; - case btMultibodyLink::eFixed: - link.joint_type = FIXED; - // random unit vector - link.body_axis_of_motion(0) = 0; - link.body_axis_of_motion(1) = 0; - link.body_axis_of_motion(2) = 1; - - // for fixed joints, m_dVector = thisPivotToThisComOffset; - // m_eVector = parentComToThisPivotOffset; - link.parent_r_parent_body_ref(0) = bt_link.m_eVector[0]; - link.parent_r_parent_body_ref(1) = bt_link.m_eVector[1]; - link.parent_r_parent_body_ref(2) = bt_link.m_eVector[2]; - break; - default: - bt_id_error_message("unknown btMultiBody::eFeatherstoneJointType %d\n", - bt_link.m_jointType); - return -1; - } - if (link.parent_index > 0) { // parent body isn't the root - const btMultibodyLink &bt_parent_link = btmb->getLink(link.parent_index - 1); - // from parent pivot to parent com, in parent frame - link.parent_r_parent_body_ref(0) += bt_parent_link.m_dVector[0]; - link.parent_r_parent_body_ref(1) += bt_parent_link.m_dVector[1]; - link.parent_r_parent_body_ref(2) += bt_parent_link.m_dVector[2]; - } else { - // parent is root body. btMultiBody only knows 6-DoF or 0-DoF root bodies, - // whose link frame is in the CoM (ie, no notion of a pivot point) - } - - if (verbose) { - id_printf("parent_r_parent_body_ref= %f %f %f\n", link.parent_r_parent_body_ref[0], - link.parent_r_parent_body_ref[1], link.parent_r_parent_body_ref[2]); - } - } - - m_initialized = true; - - return 0; -} - -int btMultiBodyTreeCreator::getNumBodies(int *num_bodies) const { - if (false == m_initialized) { - bt_id_error_message("btMultiBody not converted yet\n"); - return -1; - } - - *num_bodies = static_cast(m_data.size()); - return 0; -} - -int btMultiBodyTreeCreator::getBody(const int body_index, int *parent_index, JointType *joint_type, - vec3 *parent_r_parent_body_ref, mat33 *body_T_parent_ref, - vec3 *body_axis_of_motion, idScalar *mass, - vec3 *body_r_body_com, mat33 *body_I_body, int *user_int, - void **user_ptr) const { - if (false == m_initialized) { - bt_id_error_message("MultiBodyTree not created yet\n"); - return -1; - } - - if (body_index < 0 || body_index >= static_cast(m_data.size())) { - bt_id_error_message("index out of range (got %d but only %zu bodies)\n", body_index, - m_data.size()); - return -1; - } - - *parent_index = m_data[body_index].parent_index; - *joint_type = m_data[body_index].joint_type; - *parent_r_parent_body_ref = m_data[body_index].parent_r_parent_body_ref; - *body_T_parent_ref = m_data[body_index].body_T_parent_ref; - *body_axis_of_motion = m_data[body_index].body_axis_of_motion; - *mass = m_data[body_index].mass; - *body_r_body_com = m_data[body_index].body_r_body_com; - *body_I_body = m_data[body_index].body_I_body; - - *user_int = -1; - *user_ptr = 0x0; - - return 0; -} -} diff --git a/extern/bullet/src/Extras/InverseDynamics/btMultiBodyTreeCreator.hpp b/extern/bullet/src/Extras/InverseDynamics/btMultiBodyTreeCreator.hpp deleted file mode 100644 index dbc82ab3fb9e..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/btMultiBodyTreeCreator.hpp +++ /dev/null @@ -1,50 +0,0 @@ -#ifndef BTMULTIBODYTREECREATOR_HPP_ -#define BTMULTIBODYTREECREATOR_HPP_ - -#include - -#include "BulletInverseDynamics/IDConfig.hpp" -#include "MultiBodyTreeCreator.hpp" -#include "BulletDynamics/Featherstone/btMultiBody.h" - -namespace btInverseDynamics { - -/// MultiBodyTreeCreator implementation for converting -/// a btMultiBody forward dynamics model into a MultiBodyTree inverse dynamics model -class btMultiBodyTreeCreator : public MultiBodyTreeCreator { -public: - /// ctor - btMultiBodyTreeCreator(); - /// dtor - ~btMultiBodyTreeCreator() {} - /// extract model data from a btMultiBody - /// @param btmb pointer to btMultiBody to convert - /// @param verbose if true, some information is printed - /// @return -1 on error, 0 on success - int createFromBtMultiBody(const btMultiBody *btmb, const bool verbose = false); - /// \copydoc MultiBodyTreeCreator::getNumBodies - int getNumBodies(int *num_bodies) const; - ///\copydoc MultiBodyTreeCreator::getBody - int getBody(const int body_index, int *parent_index, JointType *joint_type, - vec3 *parent_r_parent_body_ref, mat33 *body_T_parent_ref, - vec3 *body_axis_of_motion, idScalar *mass, vec3 *body_r_body_com, - mat33 *body_I_body, int *user_int, void **user_ptr) const; - -private: - // internal struct holding data extracted from btMultiBody - struct LinkData { - int parent_index; - JointType joint_type; - vec3 parent_r_parent_body_ref; - mat33 body_T_parent_ref; - vec3 body_axis_of_motion; - idScalar mass; - vec3 body_r_body_com; - mat33 body_I_body; - }; - idArray::type m_data; - bool m_initialized; -}; -} - -#endif // BTMULTIBODYTREECREATOR_HPP_ diff --git a/extern/bullet/src/Extras/InverseDynamics/invdyn_bullet_comparison.cpp b/extern/bullet/src/Extras/InverseDynamics/invdyn_bullet_comparison.cpp deleted file mode 100644 index 4187e134bf70..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/invdyn_bullet_comparison.cpp +++ /dev/null @@ -1,307 +0,0 @@ -#include "invdyn_bullet_comparison.hpp" -#include -#include "BulletInverseDynamics/IDConfig.hpp" -#include "BulletInverseDynamics/MultiBodyTree.hpp" -#include "btBulletDynamicsCommon.h" -#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" -#include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h" -#include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h" -#include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h" - -namespace btInverseDynamics { -int compareInverseAndForwardDynamics(vecx &q, vecx &u, vecx &dot_u, btVector3 &gravity, bool verbose, - btMultiBody *btmb, MultiBodyTree *id_tree, double *pos_error, - double *acc_error) { -// call function and return -1 if it does, printing an bt_id_error_message -#define RETURN_ON_FAILURE(x) \ - do { \ - if (-1 == x) { \ - bt_id_error_message("calling " #x "\n"); \ - return -1; \ - } \ - } while (0) - - if (verbose) { - printf("\n ===================================== \n"); - } - vecx joint_forces(q.size()); - - // set positions and velocities for btMultiBody - // base link - mat33 world_T_base; - vec3 world_pos_base; - btTransform base_transform; - vec3 base_velocity; - vec3 base_angular_velocity; - - RETURN_ON_FAILURE(id_tree->setGravityInWorldFrame(gravity)); - RETURN_ON_FAILURE(id_tree->getBodyOrigin(0, &world_pos_base)); - RETURN_ON_FAILURE(id_tree->getBodyTransform(0, &world_T_base)); - RETURN_ON_FAILURE(id_tree->getBodyAngularVelocity(0, &base_angular_velocity)); - RETURN_ON_FAILURE(id_tree->getBodyLinearVelocityCoM(0, &base_velocity)); - - base_transform.setBasis(world_T_base); - base_transform.setOrigin(world_pos_base); - btmb->setBaseWorldTransform(base_transform); - btmb->setBaseOmega(base_angular_velocity); - btmb->setBaseVel(base_velocity); - btmb->setLinearDamping(0); - btmb->setAngularDamping(0); - - // remaining links - int q_index; - if (btmb->hasFixedBase()) { - q_index = 0; - } else { - q_index = 6; - } - if (verbose) { - printf("bt:num_links= %d, num_dofs= %d\n", btmb->getNumLinks(), btmb->getNumDofs()); - } - for (int l = 0; l < btmb->getNumLinks(); l++) { - const btMultibodyLink &link = btmb->getLink(l); - if (verbose) { - printf("link %d, pos_var_count= %d, dof_count= %d\n", l, link.m_posVarCount, - link.m_dofCount); - } - if (link.m_posVarCount == 1) { - btmb->setJointPosMultiDof(l, &q(q_index)); - btmb->setJointVelMultiDof(l, &u(q_index)); - if (verbose) { - printf("set q[%d]= %f, u[%d]= %f\n", q_index, q(q_index), q_index, u(q_index)); - } - q_index++; - } - } - // sanity check - if (q_index != q.size()) { - bt_id_error_message("error in number of dofs for btMultibody and MultiBodyTree\n"); - return -1; - } - - // run inverse dynamics to determine joint_forces for given q, u, dot_u - if (-1 == id_tree->calculateInverseDynamics(q, u, dot_u, &joint_forces)) { - bt_id_error_message("calculating inverse dynamics\n"); - return -1; - } - - // set up bullet forward dynamics model - btScalar dt = 0; - btAlignedObjectArray scratch_r; - btAlignedObjectArray scratch_v; - btAlignedObjectArray scratch_m; - // this triggers switch between using either appliedConstraintForce or appliedForce - bool isConstraintPass = false; - // apply gravity forces for btMultiBody model. Must be done manually. - btmb->addBaseForce(btmb->getBaseMass() * gravity); - - for (int link = 0; link < btmb->getNumLinks(); link++) { - btmb->addLinkForce(link, gravity * btmb->getLinkMass(link)); - if (verbose) { - printf("link %d, applying gravity %f %f %f\n", link, - gravity[0] * btmb->getLinkMass(link), gravity[1] * btmb->getLinkMass(link), - gravity[2] * btmb->getLinkMass(link)); - } - } - - // apply generalized forces - if (btmb->hasFixedBase()) { - q_index = 0; - } else { - vec3 base_force; - base_force(0) = joint_forces(3); - base_force(1) = joint_forces(4); - base_force(2) = joint_forces(5); - - vec3 base_moment; - base_moment(0) = joint_forces(0); - base_moment(1) = joint_forces(1); - base_moment(2) = joint_forces(2); - - btmb->addBaseForce(world_T_base * base_force); - btmb->addBaseTorque(world_T_base * base_moment); - if (verbose) { - printf("base force from id: %f %f %f\n", joint_forces(3), joint_forces(4), - joint_forces(5)); - printf("base moment from id: %f %f %f\n", joint_forces(0), joint_forces(1), - joint_forces(2)); - } - q_index = 6; - } - - for (int l = 0; l < btmb->getNumLinks(); l++) { - const btMultibodyLink &link = btmb->getLink(l); - if (link.m_posVarCount == 1) { - if (verbose) { - printf("id:joint_force[%d]= %f, applied to link %d\n", q_index, - joint_forces(q_index), l); - } - btmb->addJointTorque(l, joint_forces(q_index)); - q_index++; - } - } - - // sanity check - if (q_index != q.size()) { - bt_id_error_message("error in number of dofs for btMultibody and MultiBodyTree\n"); - return -1; - } - - // run forward kinematics & forward dynamics - btAlignedObjectArray world_to_local; - btAlignedObjectArray local_origin; - btmb->forwardKinematics(world_to_local, local_origin); - btmb->computeAccelerationsArticulatedBodyAlgorithmMultiDof(dt, scratch_r, scratch_v, scratch_m, isConstraintPass); - - // read generalized accelerations back from btMultiBody - // the mapping from scratch variables to accelerations is taken from the implementation - // of stepVelocitiesMultiDof - btScalar *base_accel = &scratch_r[btmb->getNumDofs()]; - btScalar *joint_accel = base_accel + 6; - *acc_error = 0; - int dot_u_offset = 0; - if (btmb->hasFixedBase()) { - dot_u_offset = 0; - } else { - dot_u_offset = 6; - } - - if (true == btmb->hasFixedBase()) { - for (int i = 0; i < btmb->getNumDofs(); i++) { - if (verbose) { - printf("bt:ddot_q[%d]= %f, id:ddot_q= %e, diff= %e\n", i, joint_accel[i], - dot_u(i + dot_u_offset), joint_accel[i] - dot_u(i)); - } - *acc_error += BT_ID_POW(joint_accel[i] - dot_u(i + dot_u_offset), 2); - } - } else { - vec3 base_dot_omega; - vec3 world_dot_omega; - world_dot_omega(0) = base_accel[0]; - world_dot_omega(1) = base_accel[1]; - world_dot_omega(2) = base_accel[2]; - base_dot_omega = world_T_base.transpose() * world_dot_omega; - - // com happens to coincide with link origin here. If that changes, we need to calculate - // ddot_com - vec3 base_ddot_com; - vec3 world_ddot_com; - world_ddot_com(0) = base_accel[3]; - world_ddot_com(1) = base_accel[4]; - world_ddot_com(2) = base_accel[5]; - base_ddot_com = world_T_base.transpose()*world_ddot_com; - - for (int i = 0; i < 3; i++) { - if (verbose) { - printf("bt::base_dot_omega(%d)= %e dot_u[%d]= %e, diff= %e\n", i, base_dot_omega(i), - i, dot_u[i], base_dot_omega(i) - dot_u[i]); - } - *acc_error += BT_ID_POW(base_dot_omega(i) - dot_u(i), 2); - } - for (int i = 0; i < 3; i++) { - if (verbose) { - printf("bt::base_ddot_com(%d)= %e dot_u[%d]= %e, diff= %e\n", i, base_ddot_com(i), - i, dot_u[i + 3], base_ddot_com(i) - dot_u[i + 3]); - } - *acc_error += BT_ID_POW(base_ddot_com(i) - dot_u(i + 3), 2); - } - - for (int i = 0; i < btmb->getNumDofs(); i++) { - if (verbose) { - printf("bt:ddot_q[%d]= %f, id:ddot_q= %e, diff= %e\n", i, joint_accel[i], - dot_u(i + 6), joint_accel[i] - dot_u(i + 6)); - } - *acc_error += BT_ID_POW(joint_accel[i] - dot_u(i + 6), 2); - } - } - *acc_error = std::sqrt(*acc_error); - if (verbose) { - printf("======dynamics-err: %e\n", *acc_error); - } - *pos_error = 0.0; - - { - mat33 world_T_body; - if (-1 == id_tree->getBodyTransform(0, &world_T_body)) { - bt_id_error_message("getting transform for body %d\n", 0); - return -1; - } - vec3 world_com; - if (-1 == id_tree->getBodyCoM(0, &world_com)) { - bt_id_error_message("getting com for body %d\n", 0); - return -1; - } - if (verbose) { - printf("id:com: %f %f %f\n", world_com(0), world_com(1), world_com(2)); - - printf("id:transform: %f %f %f\n" - " %f %f %f\n" - " %f %f %f\n", - world_T_body(0, 0), world_T_body(0, 1), world_T_body(0, 2), world_T_body(1, 0), - world_T_body(1, 1), world_T_body(1, 2), world_T_body(2, 0), world_T_body(2, 1), - world_T_body(2, 2)); - } - } - - for (int l = 0; l < btmb->getNumLinks(); l++) { - const btMultibodyLink &bt_link = btmb->getLink(l); - - vec3 bt_origin = bt_link.m_cachedWorldTransform.getOrigin(); - mat33 bt_basis = bt_link.m_cachedWorldTransform.getBasis(); - if (verbose) { - printf("------------- link %d\n", l + 1); - printf("bt:com: %f %f %f\n", bt_origin(0), bt_origin(1), bt_origin(2)); - printf("bt:transform: %f %f %f\n" - " %f %f %f\n" - " %f %f %f\n", - bt_basis(0, 0), bt_basis(0, 1), bt_basis(0, 2), bt_basis(1, 0), bt_basis(1, 1), - bt_basis(1, 2), bt_basis(2, 0), bt_basis(2, 1), bt_basis(2, 2)); - } - mat33 id_world_T_body; - vec3 id_world_com; - - if (-1 == id_tree->getBodyTransform(l + 1, &id_world_T_body)) { - bt_id_error_message("getting transform for body %d\n", l); - return -1; - } - if (-1 == id_tree->getBodyCoM(l + 1, &id_world_com)) { - bt_id_error_message("getting com for body %d\n", l); - return -1; - } - if (verbose) { - printf("id:com: %f %f %f\n", id_world_com(0), id_world_com(1), id_world_com(2)); - - printf("id:transform: %f %f %f\n" - " %f %f %f\n" - " %f %f %f\n", - id_world_T_body(0, 0), id_world_T_body(0, 1), id_world_T_body(0, 2), - id_world_T_body(1, 0), id_world_T_body(1, 1), id_world_T_body(1, 2), - id_world_T_body(2, 0), id_world_T_body(2, 1), id_world_T_body(2, 2)); - } - vec3 diff_com = bt_origin - id_world_com; - mat33 diff_basis = bt_basis - id_world_T_body; - if (verbose) { - printf("diff-com: %e %e %e\n", diff_com(0), diff_com(1), diff_com(2)); - - printf("diff-transform: %e %e %e %e %e %e %e %e %e\n", diff_basis(0, 0), - diff_basis(0, 1), diff_basis(0, 2), diff_basis(1, 0), diff_basis(1, 1), - diff_basis(1, 2), diff_basis(2, 0), diff_basis(2, 1), diff_basis(2, 2)); - } - double total_pos_err = - BT_ID_SQRT(BT_ID_POW(diff_com(0), 2) + BT_ID_POW(diff_com(1), 2) + - BT_ID_POW(diff_com(2), 2) + BT_ID_POW(diff_basis(0, 0), 2) + - BT_ID_POW(diff_basis(0, 1), 2) + BT_ID_POW(diff_basis(0, 2), 2) + - BT_ID_POW(diff_basis(1, 0), 2) + BT_ID_POW(diff_basis(1, 1), 2) + - BT_ID_POW(diff_basis(1, 2), 2) + BT_ID_POW(diff_basis(2, 0), 2) + - BT_ID_POW(diff_basis(2, 1), 2) + BT_ID_POW(diff_basis(2, 2), 2)); - if (verbose) { - printf("======kin-pos-err: %e\n", total_pos_err); - } - if (total_pos_err > *pos_error) { - *pos_error = total_pos_err; - } - } - - return 0; -} -} diff --git a/extern/bullet/src/Extras/InverseDynamics/invdyn_bullet_comparison.hpp b/extern/bullet/src/Extras/InverseDynamics/invdyn_bullet_comparison.hpp deleted file mode 100644 index 1a6b7d4d5657..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/invdyn_bullet_comparison.hpp +++ /dev/null @@ -1,35 +0,0 @@ -#ifndef INVDYN_BULLET_COMPARISON_HPP -#define INVDYN_BULLET_COMPARISON_HPP - -#include "BulletInverseDynamics/IDConfig.hpp" - -class btMultiBody; -class btVector3; - -namespace btInverseDynamics { -class MultiBodyTree; - -/// this function compares the forward dynamics computations implemented in btMultiBody to -/// the inverse dynamics implementation in MultiBodyTree. This is done in three steps -/// 1. run inverse dynamics for (q, u, dot_u) to obtain joint forces f -/// 2. run forward dynamics (btMultiBody) for (q,u,f) to obtain dot_u_bullet -/// 3. compare dot_u with dot_u_bullet for cross check of forward and inverse dynamics computations -/// @param btmb the bullet forward dynamics model -/// @param id_tree the inverse dynamics model -/// @param q vector of generalized coordinates (matches id_tree) -/// @param u vector of generalized speeds (matches id_tree) -/// @param gravity gravitational acceleration in world frame -/// @param dot_u vector of generalized accelerations (matches id_tree) -/// @param gravity gravitational acceleration in world frame -/// @param base_fixed set base joint to fixed or -/// @param pos_error is set to the maximum of the euclidean norm of position+rotation errors of all -/// center of gravity positions and link frames -/// @param acc_error is set to the square root of the sum of squared differences of generalized -/// accelerations -/// computed in step 3 relative to dot_u -/// @return -1 on error, 0 on success -int compareInverseAndForwardDynamics(vecx &q, vecx &u, vecx &dot_u, btVector3 &gravity, bool verbose, - btMultiBody *btmb, MultiBodyTree *id_tree, double *pos_error, - double *acc_error); -} -#endif // INVDYN_BULLET_COMPARISON_HPP diff --git a/extern/bullet/src/Extras/InverseDynamics/premake4.lua b/extern/bullet/src/Extras/InverseDynamics/premake4.lua deleted file mode 100644 index c1e263bfb43e..000000000000 --- a/extern/bullet/src/Extras/InverseDynamics/premake4.lua +++ /dev/null @@ -1,15 +0,0 @@ - project "BulletInverseDynamicsUtils" - - kind "StaticLib" - - includedirs { - "../../src" - } - - if os.is("Linux") then - buildoptions{"-fPIC"} - end - files { - "*.cpp", - "*.hpp" - } diff --git a/extern/bullet/src/Extras/Makefile.am b/extern/bullet/src/Extras/Makefile.am deleted file mode 100644 index f4cd5eac827c..000000000000 --- a/extern/bullet/src/Extras/Makefile.am +++ /dev/null @@ -1,95 +0,0 @@ -noinst_LIBRARIES = libgimpactutils.a libconvexdecomposition.a libHACD.a libglui.a - -libglui_a_CXXFLAGS = ${CXXFLAGS} -Iglui -libglui_a_SOURCES =\ - glui/glui_spinner.cpp\ - glui/glui_treepanel.cpp\ - glui/arcball.cpp\ - glui/glui_scrollbar.cpp\ - glui/glui_filebrowser.cpp\ - glui/glui_node.cpp\ - glui/glui_edittext.cpp\ - glui/glui_statictext.cpp\ - glui/glui_bitmaps.cpp\ - glui/algebra3.cpp\ - glui/glui_string.cpp\ - glui/glui_button.cpp\ - glui/glui_add_controls.cpp\ - glui/glui_control.cpp\ - glui/glui.cpp\ - glui/glui_listbox.cpp\ - glui/glui_checkbox.cpp\ - glui/glui_commandline.cpp\ - glui/glui_textbox.cpp\ - glui/glui_column.cpp\ - glui/glui_mouse_iaction.cpp\ - glui/glui_radio.cpp\ - glui/glui_translation.cpp\ - glui/glui_tree.cpp\ - glui/glui_rotation.cpp\ - glui/glui_panel.cpp\ - glui/glui_rollout.cpp\ - glui/glui_separator.cpp\ - glui/glui_bitmap_img_data.cpp\ - glui/quaternion.cpp\ - glui/glui_window.cpp\ - glui/glui_list.cpp\ - glui/GL/glui.h\ - glui/quaternion.h\ - glui/glui_internal.h\ - glui/glui_internal_control.h\ - glui/arcball.h\ - glui/algebra3.h - -libconvexdecomposition_a_CXXFLAGS = ${CXXFLAGS} -IConvexDecomposition/ -I../src -libconvexdecomposition_a_SOURCES =\ - ConvexDecomposition/concavity.cpp\ - ConvexDecomposition/ConvexDecomposition.cpp\ - ConvexDecomposition/vlookup.cpp\ - ConvexDecomposition/bestfit.cpp\ - ConvexDecomposition/ConvexBuilder.cpp\ - ConvexDecomposition/cd_hull.cpp\ - ConvexDecomposition/raytri.cpp\ - ConvexDecomposition/splitplane.cpp\ - ConvexDecomposition/float_math.cpp\ - ConvexDecomposition/planetri.cpp\ - ConvexDecomposition/cd_wavefront.cpp\ - ConvexDecomposition/bestfitobb.cpp\ - ConvexDecomposition/meshvolume.cpp\ - ConvexDecomposition/fitsphere.cpp\ - ConvexDecomposition/fitsphere.h\ - ConvexDecomposition/vlookup.h\ - ConvexDecomposition/concavity.h\ - ConvexDecomposition/ConvexDecomposition.h\ - ConvexDecomposition/bestfit.h\ - ConvexDecomposition/cd_vector.h\ - ConvexDecomposition/ConvexBuilder.h\ - ConvexDecomposition/cd_hull.h\ - ConvexDecomposition/raytri.h\ - ConvexDecomposition/splitplane.h\ - ConvexDecomposition/float_math.h\ - ConvexDecomposition/planetri.h\ - ConvexDecomposition/cd_wavefront.h\ - ConvexDecomposition/bestfitobb.h\ - ConvexDecomposition/meshvolume.h - -libHACD_a_CXXFLAGS = ${CXXFLAGS} -IHACD/ -I../src -libHACD_a_SOURCES =\ - HACD/hacdGraph.cpp\ - HACD/hacdHACD.cpp\ - HACD/hacdICHull.cpp\ - HACD/hacdManifoldMesh.cpp\ - HACD/hacdCircularList.h\ - HACD/hacdGraph.h\ - HACD/hacdHACD.h\ - HACD/hacdICHull.h\ - HACD/hacdManifoldMesh.h\ - HACD/hacdVector.h\ - HACD/hacdVersion.h\ - HACD/hacdCircularList.inl\ - HACD/hacdVector.inl - - -libgimpactutils_a_CXXFLAGS = ${CXXFLAGS} -I../src -IGIMPACTUtils -IConvexDecomposition -libgimpactutils_a_SOURCES = GIMPACTUtils/btGImpactConvexDecompositionShape.cpp GIMPACTUtils/btGImpactConvexDecompositionShape.h - diff --git a/extern/bullet/src/Extras/Serialize/BlenderSerialize/CMakeLists.txt b/extern/bullet/src/Extras/Serialize/BlenderSerialize/CMakeLists.txt deleted file mode 100644 index 4c75188f2aae..000000000000 --- a/extern/bullet/src/Extras/Serialize/BlenderSerialize/CMakeLists.txt +++ /dev/null @@ -1,7 +0,0 @@ -INCLUDE_DIRECTORIES( ${BULLET_PHYSICS_SOURCE_DIR}/src -${BULLET_PHYSICS_SOURCE_DIR}/src -${BULLET_PHYSICS_SOURCE_DIR}/Extras/Serialize/BulletFileLoader -${BULLET_PHYSICS_SOURCE_DIR}/Extras/Serialize/BlenderSerialize -) - -ADD_LIBRARY(BlenderSerialize dna249.cpp dna249-64bit.cpp bBlenderFile.cpp bBlenderFile.h bMain.cpp bMain.h ) diff --git a/extern/bullet/src/Extras/Serialize/BlenderSerialize/bBlenderFile.cpp b/extern/bullet/src/Extras/Serialize/BlenderSerialize/bBlenderFile.cpp deleted file mode 100644 index 9405fe14f1da..000000000000 --- a/extern/bullet/src/Extras/Serialize/BlenderSerialize/bBlenderFile.cpp +++ /dev/null @@ -1,225 +0,0 @@ -/* -bParse -Copyright (c) 2006-2009 Charlie C & Erwin Coumans http://gamekit.googlecode.com - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#include "bBlenderFile.h" -#include "bMain.h" -#include "bDefines.h" -#include "bDNA.h" -#include -#include - -// 32 && 64 bit versions -extern unsigned char DNAstr[]; -extern int DNAlen; - -extern unsigned char DNAstr64[]; -extern int DNAlen64; - - -using namespace bParse; - -bBlenderFile::bBlenderFile(const char* fileName) -:bFile(fileName, "BLENDER") -{ - mMain= new bMain(this, fileName, mVersion); -} - - - -bBlenderFile::bBlenderFile(char *memoryBuffer, int len) -:bFile(memoryBuffer,len, "BLENDER"), -mMain(0) -{ - mMain= new bMain(this, "memoryBuf", mVersion); -} - - -bBlenderFile::~bBlenderFile() -{ - delete mMain; -} - - -bMain* bBlenderFile::getMain() -{ - return mMain; -} - -// ----------------------------------------------------- // -void bBlenderFile::parseData() -{ -// printf ("Building datablocks\n"); -// printf ("Chunk size = %d\n",CHUNK_HEADER_LEN); -// printf ("File chunk size = %d\n", ChunkUtils::getOffset(mFlags)); - - const bool swap = (mFlags&FD_ENDIAN_SWAP)!=0; - - - - char *dataPtr = mFileBuffer+mDataStart; - - bChunkInd dataChunk; - dataChunk.code = 0; - - - //dataPtr += ChunkUtils::getNextBlock(&dataChunk, dataPtr, mFlags); - int seek = getNextBlock(&dataChunk, dataPtr, mFlags); - //dataPtr += ChunkUtils::getOffset(mFlags); - char *dataPtrHead = 0; - - while (dataChunk.code != DNA1) - { - - - - - // one behind - if (dataChunk.code == SDNA) break; - //if (dataChunk.code == DNA1) break; - - // same as (BHEAD+DATA dependency) - dataPtrHead = dataPtr+ChunkUtils::getOffset(mFlags); - char *id = readStruct(dataPtrHead, dataChunk); - - // lookup maps - if (id) - { - m_chunkPtrPtrMap.insert(dataChunk.oldPtr, dataChunk); - mLibPointers.insert(dataChunk.oldPtr, (bStructHandle*)id); - - m_chunks.push_back(dataChunk); - // block it - bListBasePtr *listID = mMain->getListBasePtr(dataChunk.code); - if (listID) - listID->push_back((bStructHandle*)id); - } - - if (dataChunk.code == GLOB) - { - m_glob = (bStructHandle*) id; - } - - // next please! - dataPtr += seek; - - seek = getNextBlock(&dataChunk, dataPtr, mFlags); - if (seek < 0) - break; - } - -} - -void bBlenderFile::addDataBlock(char* dataBlock) -{ - mMain->addDatablock(dataBlock); -} - - - - - -// 32 && 64 bit versions -extern unsigned char DNAstr[]; -extern int DNAlen; - -//unsigned char DNAstr[]={0}; -//int DNAlen=0; - - -extern unsigned char DNAstr64[]; -extern int DNAlen64; - - -void bBlenderFile::writeDNA(FILE* fp) -{ - - bChunkInd dataChunk; - dataChunk.code = DNA1; - dataChunk.dna_nr = 0; - dataChunk.nr = 1; - - if (VOID_IS_8) - { - dataChunk.len = DNAlen64; - dataChunk.oldPtr = DNAstr64; - fwrite(&dataChunk,sizeof(bChunkInd),1,fp); - fwrite(DNAstr64, DNAlen64,1,fp); - } - else - { - dataChunk.len = DNAlen; - dataChunk.oldPtr = DNAstr; - fwrite(&dataChunk,sizeof(bChunkInd),1,fp); - fwrite(DNAstr, DNAlen,1,fp); - } -} - -void bBlenderFile::parse(int verboseMode) -{ - if (VOID_IS_8) - { - parseInternal(verboseMode,(char*)DNAstr64,DNAlen64); - } - else - { - parseInternal(verboseMode,(char*)DNAstr,DNAlen); - } -} - -// experimental -int bBlenderFile::write(const char* fileName, bool fixupPointers) -{ - FILE *fp = fopen(fileName, "wb"); - if (fp) - { - char header[SIZEOFBLENDERHEADER] ; - memcpy(header, m_headerString, 7); - int endian= 1; - endian= ((char*)&endian)[0]; - - if (endian) - { - header[7] = '_'; - } else - { - header[7] = '-'; - } - if (VOID_IS_8) - { - header[8]='V'; - } else - { - header[8]='v'; - } - - header[9] = '2'; - header[10] = '4'; - header[11] = '9'; - - fwrite(header,SIZEOFBLENDERHEADER,1,fp); - - writeChunks(fp, fixupPointers); - - writeDNA(fp); - - fclose(fp); - - } else - { - printf("Error: cannot open file %s for writing\n",fileName); - return 0; - } - return 1; -} \ No newline at end of file diff --git a/extern/bullet/src/Extras/Serialize/BlenderSerialize/bBlenderFile.h b/extern/bullet/src/Extras/Serialize/BlenderSerialize/bBlenderFile.h deleted file mode 100644 index 3c163b9e14b7..000000000000 --- a/extern/bullet/src/Extras/Serialize/BlenderSerialize/bBlenderFile.h +++ /dev/null @@ -1,63 +0,0 @@ -/* -bParse -Copyright (c) 2006-2009 Charlie C & Erwin Coumans http://gamekit.googlecode.com - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#ifndef B_BLENDER_FILE_H -#define B_BLENDER_FILE_H - - -#include "bFile.h" - -namespace bParse { - - // ----------------------------------------------------- // - class bBlenderFile : public bFile - { - - protected: - bMain* mMain; - - bStructHandle* m_glob; - - - public: - - bBlenderFile(const char* fileName); - - bBlenderFile(char *memoryBuffer, int len); - - virtual ~bBlenderFile(); - - bMain* getMain(); - - virtual void addDataBlock(char* dataBlock); - - bStructHandle* getFileGlobal() - { - return m_glob; - } - - // experimental - virtual int write(const char* fileName, bool fixupPointers = false); - - virtual void parse(int verboseMode); - - virtual void parseData(); - - virtual void writeDNA(FILE* fp); - - }; -}; - -#endif //B_BLENDER_FILE_H diff --git a/extern/bullet/src/Extras/Serialize/BlenderSerialize/bMain.cpp b/extern/bullet/src/Extras/Serialize/BlenderSerialize/bMain.cpp deleted file mode 100644 index fa672fbb87df..000000000000 --- a/extern/bullet/src/Extras/Serialize/BlenderSerialize/bMain.cpp +++ /dev/null @@ -1,392 +0,0 @@ -/* -bParse -Copyright (c) 2006-2009 Charlie C & Erwin Coumans http://gamekit.googlecode.com - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#include "bMain.h" -#include "bBlenderFile.h" -#include "bDefines.h" -#include "bChunk.h" -#include "bDNA.h" - -using namespace bParse; - - -// ----------------------------------------------------- // -bMain::bMain(bBlenderFile *filePtr, const char *baseName, int fileVersion) - : mFP(filePtr), - mVersion(fileVersion), - mName(baseName) -{ - mData.insert(ID_SCE,bListBasePtr()); - mData.insert(ID_LI,bListBasePtr()); - mData.insert(ID_OB,bListBasePtr()); - mData.insert(ID_ME,bListBasePtr()); - mData.insert(ID_CU,bListBasePtr()); - mData.insert(ID_MB,bListBasePtr()); - mData.insert(ID_MA,bListBasePtr()); - mData.insert(ID_TE,bListBasePtr()); - mData.insert(ID_IM,bListBasePtr()); - mData.insert(ID_WV,bListBasePtr()); - mData.insert(ID_LT,bListBasePtr()); - mData.insert(ID_LA,bListBasePtr()); - mData.insert(ID_CA,bListBasePtr()); - mData.insert(ID_IP,bListBasePtr()); - mData.insert(ID_KE,bListBasePtr()); - mData.insert(ID_WO,bListBasePtr()); - mData.insert(ID_SCR,bListBasePtr()); - mData.insert(ID_VF,bListBasePtr()); - mData.insert(ID_TXT,bListBasePtr()); - mData.insert(ID_SO,bListBasePtr()); - mData.insert(ID_GR,bListBasePtr()); - mData.insert(ID_AR,bListBasePtr()); - mData.insert(ID_AC,bListBasePtr()); - mData.insert(ID_NT,bListBasePtr()); - mData.insert(ID_BR,bListBasePtr()); - mData.insert(ID_SCRIPT, bListBasePtr()); -} - - -// ----------------------------------------------------- // -bMain::~bMain() -{ - // allocated data blocks! - - int sz = mPool.size(); - for (int i=0;ifirst) - return; - - base->first = mFP->findLibPointer(base->first); - if (!base->first) - { - base->last = 0; - return; - } - - void *prev = 0; - Link *l = (Link*)base->first; - while (l) - { - l->next = mFP->findLibPointer(l->next); - l->prev = l->next; - prev = l->next; - l = (Link*)l->next; - } -} - -// ------------------------------------------------------------// -bListBasePtr* bMain::getListBasePtr(int listBaseCode) -{ - bListBasePtr *ptr = _findCode(listBaseCode); - if (!ptr) - return 0; - return ptr; -} - -// ------------------------------------------------------------// -bListBasePtr *bMain::_findCode(int code) -{ - - bListBasePtr* lbPtr = mData.find(code); - return lbPtr; -} - - -// ------------------------------------------------------------// -bListBasePtr *bMain::getScene() -{ - bListBasePtr *ptr = _findCode(ID_SCE); - if (!ptr) - return 0; - return ptr; -} - -// ------------------------------------------------------------// -bListBasePtr *bMain::getLibrary() -{ - bListBasePtr *ptr = _findCode(ID_LI); - if (!ptr) - return 0; - return ptr; -} -// ------------------------------------------------------------// -bListBasePtr *bMain::getObject() -{ - bListBasePtr *ptr = _findCode(ID_OB); - if (!ptr) - return 0; - return ptr; -} - -// ------------------------------------------------------------// -bListBasePtr *bMain::getMesh() -{ - bListBasePtr *ptr = _findCode(ID_ME); - if (!ptr) - return 0; - return ptr; -} - -// ------------------------------------------------------------// -bListBasePtr *bMain::getCurve() -{ - bListBasePtr *ptr = _findCode(ID_CU); - if (!ptr) - return 0; - return ptr; -} - - - -// ------------------------------------------------------------// -bListBasePtr *bMain::getMball() -{ - bListBasePtr *ptr = _findCode(ID_MB); - if (!ptr) - return 0; - return ptr; -} - -// ------------------------------------------------------------// -bListBasePtr *bMain::getMat() -{ - bListBasePtr *ptr = _findCode(ID_MA); - if (!ptr) - return 0; - return ptr; -} - -// ------------------------------------------------------------// -bListBasePtr *bMain::getTex() -{ - bListBasePtr *ptr = _findCode(ID_TE); - if (!ptr) - return 0; - return ptr; -} - - -// ------------------------------------------------------------// -bListBasePtr *bMain::getImage() -{ - bListBasePtr *ptr = _findCode(ID_IM); - if (!ptr) - return 0; - return ptr; -} - -// ------------------------------------------------------------// -bListBasePtr *bMain::getWave() -{ - bListBasePtr *ptr = _findCode(ID_WV); - if (!ptr) - return 0; - return ptr; -} - -// ------------------------------------------------------------// -bListBasePtr *bMain::getLatt() -{ - bListBasePtr *ptr = _findCode(ID_LT); - if (!ptr) - return 0; - return ptr; -} - -// ------------------------------------------------------------// -bListBasePtr *bMain::getLamp() -{ - bListBasePtr *ptr = _findCode(ID_LA); - if (!ptr) - return 0; - return ptr; -} - -// ------------------------------------------------------------// -bListBasePtr *bMain::getCamera() -{ - bListBasePtr *ptr = _findCode(ID_CA); - if (!ptr) - return 0; - return ptr; -} - -// ------------------------------------------------------------// -bListBasePtr *bMain::getIpo() -{ - bListBasePtr *ptr = _findCode(ID_IP); - if (!ptr) - return 0; - return ptr; -} - -// ------------------------------------------------------------// -bListBasePtr *bMain::getKey() -{ - bListBasePtr *ptr = _findCode(ID_KE); - if (!ptr) - return 0; - return ptr; -} - -// ------------------------------------------------------------// -bListBasePtr *bMain::getWorld() -{ - bListBasePtr *ptr = _findCode(ID_WO); - if (!ptr) - return 0; - return ptr; -} - - -// ------------------------------------------------------------// -bListBasePtr *bMain::getScreen() -{ - bListBasePtr *ptr = _findCode(ID_SCR); - if (!ptr) - return 0; - return ptr; -} - -// ------------------------------------------------------------// -bListBasePtr *bMain::getScript() -{ - bListBasePtr *ptr = _findCode(ID_SCRIPT); - if (!ptr) - return 0; - return ptr; -} - -// ------------------------------------------------------------// -bListBasePtr *bMain::getVfont() -{ - bListBasePtr *ptr = _findCode(ID_VF); - if (!ptr) - return 0; - return ptr; -} - -// ------------------------------------------------------------// -bListBasePtr *bMain::getText() -{ - bListBasePtr *ptr = _findCode(ID_TXT); - if (!ptr) - return 0; - return ptr; -} - -// ------------------------------------------------------------// -bListBasePtr *bMain::getSound() -{ - bListBasePtr *ptr = _findCode(ID_SO); - if (!ptr) - return 0; - return ptr; -} - -// ------------------------------------------------------------// -bListBasePtr *bMain::getGroup() -{ - bListBasePtr *ptr = _findCode(ID_GR); - if (!ptr) - return 0; - return ptr; -} - -// ------------------------------------------------------------// -bListBasePtr *bMain::getArmature() -{ - bListBasePtr *ptr = _findCode(ID_AR); - if (!ptr) - return 0; - return ptr; -} - -// ------------------------------------------------------------// -bListBasePtr *bMain::getAction() -{ - bListBasePtr *ptr = _findCode(ID_AC); - if (!ptr) - return 0; - return ptr; -} - - -// ------------------------------------------------------------// -bListBasePtr *bMain::getNodetree() -{ - bListBasePtr *ptr = _findCode(ID_NT); - if (!ptr) - return 0; - return ptr; -} - -// ------------------------------------------------------------// -bListBasePtr *bMain::getBrush() -{ - bListBasePtr *ptr = _findCode(ID_BR); - if (!ptr) - return 0; - return ptr; -} - - - -//eof diff --git a/extern/bullet/src/Extras/Serialize/BlenderSerialize/bMain.h b/extern/bullet/src/Extras/Serialize/BlenderSerialize/bMain.h deleted file mode 100644 index f8e9afc5b825..000000000000 --- a/extern/bullet/src/Extras/Serialize/BlenderSerialize/bMain.h +++ /dev/null @@ -1,110 +0,0 @@ -/* -bParse -Copyright (c) 2006-2009 Charlie C & Erwin Coumans http://gamekit.googlecode.com - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#ifndef __BMAIN_H__ -#define __BMAIN_H__ - -#include "bCommon.h" -#include "bChunk.h" -#include "LinearMath/btHashMap.h" - - -namespace bParse -{ - class bDNA; - - class bBlenderFile; -}; - - - -namespace bParse { - - - // ----------------------------------------------------- // - - typedef btHashMap bMainDataMap; - - - - // ----------------------------------------------------- // - class bMain - { - //private: - public: - bBlenderFile* mFP; - bListBasePtr mPool; - - int mVersion; - const char* mName; - - bMainDataMap mData; - - - - - bListBasePtr *_findCode(int code); - - public: - bMain(bBlenderFile *filePtr, const char *baseName, int fileVersion); - ~bMain(); - - int getVersion(); - const char *getName(); - - bListBasePtr *getListBasePtr(int listBaseCode); - - - bListBasePtr *getScene(); - bListBasePtr *getLibrary(); - bListBasePtr *getObject(); - bListBasePtr *getMesh(); - bListBasePtr *getCurve(); - bListBasePtr *getMball(); - bListBasePtr *getMat(); - bListBasePtr *getTex(); - bListBasePtr *getImage(); - bListBasePtr *getWave(); - bListBasePtr *getLatt(); - bListBasePtr *getLamp(); - bListBasePtr *getCamera(); - bListBasePtr *getIpo(); - bListBasePtr *getKey(); - bListBasePtr *getWorld(); - bListBasePtr *getScreen(); - bListBasePtr *getScript(); - bListBasePtr *getVfont(); - bListBasePtr *getText(); - bListBasePtr *getSound(); - bListBasePtr *getGroup(); - bListBasePtr *getArmature(); - bListBasePtr *getAction(); - bListBasePtr *getNodetree(); - bListBasePtr *getBrush(); - - - - // tracking allocated memory - void addDatablock(void *allocated); - - - // -- - - void linkList(void *listBasePtr); - }; -} - - -#endif//__BMAIN_H__ diff --git a/extern/bullet/src/Extras/Serialize/BlenderSerialize/dna249-64bit.cpp b/extern/bullet/src/Extras/Serialize/BlenderSerialize/dna249-64bit.cpp deleted file mode 100644 index 7c56c2c470e4..000000000000 --- a/extern/bullet/src/Extras/Serialize/BlenderSerialize/dna249-64bit.cpp +++ /dev/null @@ -1,1411 +0,0 @@ -/* -bParse -Copyright (c) 2006-2009 Charlie C & Erwin Coumans http://gamekit.googlecode.com - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ -unsigned char DNAstr64[]= { -83,68,78,65,78,65,77,69,119,9,0,0,42,110,101,120,116,0,42,112,114,101,118,0,42,100,97,116,97,0,42,102,105, -114,115,116,0,42,108,97,115,116,0,120,0,121,0,122,0,119,0,120,109,105,110,0,120,109,97,120,0,121,109,105,110, -0,121,109,97,120,0,42,112,111,105,110,116,101,114,0,103,114,111,117,112,0,118,97,108,0,118,97,108,50,0,110,97, -109,101,91,51,50,93,0,116,121,112,101,0,115,117,98,116,121,112,101,0,102,108,97,103,0,115,97,118,101,100,0,100, -97,116,97,0,108,101,110,0,116,111,116,97,108,108,101,110,0,42,110,101,119,105,100,0,42,108,105,98,0,110,97,109, -101,91,50,52,93,0,117,115,0,105,99,111,110,95,105,100,0,42,112,114,111,112,101,114,116,105,101,115,0,105,100,0, -42,105,100,98,108,111,99,107,0,42,102,105,108,101,100,97,116,97,0,110,97,109,101,91,50,52,48,93,0,102,105,108, -101,110,97,109,101,91,50,52,48,93,0,116,111,116,0,112,97,100,0,42,112,97,114,101,110,116,0,119,91,50,93,0, -104,91,50,93,0,99,104,97,110,103,101,100,91,50,93,0,112,97,100,48,0,112,97,100,49,0,42,114,101,99,116,91, -50,93,0,42,111,98,0,98,108,111,99,107,116,121,112,101,0,97,100,114,99,111,100,101,0,110,97,109,101,91,49,50, -56,93,0,42,98,112,0,42,98,101,122,116,0,109,97,120,114,99,116,0,116,111,116,114,99,116,0,118,97,114,116,121, -112,101,0,116,111,116,118,101,114,116,0,105,112,111,0,101,120,116,114,97,112,0,114,116,0,98,105,116,109,97,115,107, -0,115,108,105,100,101,95,109,105,110,0,115,108,105,100,101,95,109,97,120,0,99,117,114,118,97,108,0,42,100,114,105, -118,101,114,0,99,117,114,118,101,0,99,117,114,0,115,104,111,119,107,101,121,0,109,117,116,101,105,112,111,0,112,111, -115,0,114,101,108,97,116,105,118,101,0,116,111,116,101,108,101,109,0,112,97,100,50,0,42,119,101,105,103,104,116,115, -0,118,103,114,111,117,112,91,51,50,93,0,115,108,105,100,101,114,109,105,110,0,115,108,105,100,101,114,109,97,120,0, -42,114,101,102,107,101,121,0,101,108,101,109,115,116,114,91,51,50,93,0,101,108,101,109,115,105,122,101,0,98,108,111, -99,107,0,42,105,112,111,0,42,102,114,111,109,0,116,111,116,107,101,121,0,115,108,117,114,112,104,0,42,42,115,99, -114,105,112,116,115,0,42,102,108,97,103,0,97,99,116,115,99,114,105,112,116,0,116,111,116,115,99,114,105,112,116,0, -42,108,105,110,101,0,42,102,111,114,109,97,116,0,98,108,101,110,0,108,105,110,101,110,111,0,115,116,97,114,116,0, -101,110,100,0,102,108,97,103,115,0,99,111,108,111,114,91,52,93,0,112,97,100,91,52,93,0,42,110,97,109,101,0, -110,108,105,110,101,115,0,108,105,110,101,115,0,42,99,117,114,108,0,42,115,101,108,108,0,99,117,114,99,0,115,101, -108,99,0,109,97,114,107,101,114,115,0,42,117,110,100,111,95,98,117,102,0,117,110,100,111,95,112,111,115,0,117,110, -100,111,95,108,101,110,0,42,99,111,109,112,105,108,101,100,0,109,116,105,109,101,0,115,105,122,101,0,115,101,101,107, -0,112,97,115,115,101,112,97,114,116,97,108,112,104,97,0,97,110,103,108,101,0,99,108,105,112,115,116,97,0,99,108, -105,112,101,110,100,0,108,101,110,115,0,111,114,116,104,111,95,115,99,97,108,101,0,100,114,97,119,115,105,122,101,0, -115,104,105,102,116,120,0,115,104,105,102,116,121,0,89,70,95,100,111,102,100,105,115,116,0,89,70,95,97,112,101,114, -116,117,114,101,0,89,70,95,98,107,104,116,121,112,101,0,89,70,95,98,107,104,98,105,97,115,0,89,70,95,98,107, -104,114,111,116,0,115,99,114,105,112,116,108,105,110,107,0,42,100,111,102,95,111,98,0,102,114,97,109,101,110,114,0, -102,114,97,109,101,115,0,111,102,102,115,101,116,0,115,102,114,97,0,102,105,101,95,105,109,97,0,99,121,99,108,0, -111,107,0,109,117,108,116,105,95,105,110,100,101,120,0,108,97,121,101,114,0,112,97,115,115,0,109,101,110,117,110,114, -0,105,98,117,102,115,0,42,103,112,117,116,101,120,116,117,114,101,0,42,97,110,105,109,0,42,114,114,0,115,111,117, -114,99,101,0,108,97,115,116,102,114,97,109,101,0,116,112,97,103,101,102,108,97,103,0,116,111,116,98,105,110,100,0, -120,114,101,112,0,121,114,101,112,0,116,119,115,116,97,0,116,119,101,110,100,0,98,105,110,100,99,111,100,101,0,42, -114,101,112,98,105,110,100,0,42,112,97,99,107,101,100,102,105,108,101,0,42,112,114,101,118,105,101,119,0,108,97,115, -116,117,112,100,97,116,101,0,108,97,115,116,117,115,101,100,0,97,110,105,109,115,112,101,101,100,0,103,101,110,95,120, -0,103,101,110,95,121,0,103,101,110,95,116,121,112,101,0,97,115,112,120,0,97,115,112,121,0,42,118,110,111,100,101, -0,116,101,120,99,111,0,109,97,112,116,111,0,109,97,112,116,111,110,101,103,0,98,108,101,110,100,116,121,112,101,0, -42,111,98,106,101,99,116,0,42,116,101,120,0,117,118,110,97,109,101,91,51,50,93,0,112,114,111,106,120,0,112,114, -111,106,121,0,112,114,111,106,122,0,109,97,112,112,105,110,103,0,111,102,115,91,51,93,0,115,105,122,101,91,51,93, -0,116,101,120,102,108,97,103,0,99,111,108,111,114,109,111,100,101,108,0,112,109,97,112,116,111,0,112,109,97,112,116, -111,110,101,103,0,110,111,114,109,97,112,115,112,97,99,101,0,119,104,105,99,104,95,111,117,116,112,117,116,0,112,97, -100,91,50,93,0,114,0,103,0,98,0,107,0,100,101,102,95,118,97,114,0,99,111,108,102,97,99,0,110,111,114,102, -97,99,0,118,97,114,102,97,99,0,100,105,115,112,102,97,99,0,119,97,114,112,102,97,99,0,110,97,109,101,91,49, -54,48,93,0,42,104,97,110,100,108,101,0,42,112,110,97,109,101,0,42,115,116,110,97,109,101,115,0,115,116,121,112, -101,115,0,118,97,114,115,0,42,118,97,114,115,116,114,0,42,114,101,115,117,108,116,0,42,99,102,114,97,0,100,97, -116,97,91,51,50,93,0,40,42,100,111,105,116,41,40,41,0,40,42,105,110,115,116,97,110,99,101,95,105,110,105,116, -41,40,41,0,40,42,99,97,108,108,98,97,99,107,41,40,41,0,118,101,114,115,105,111,110,0,97,0,105,112,111,116, -121,112,101,0,42,105,109,97,0,42,99,117,98,101,91,54,93,0,105,109,97,116,91,52,93,91,52,93,0,111,98,105, -109,97,116,91,51,93,91,51,93,0,115,116,121,112,101,0,118,105,101,119,115,99,97,108,101,0,110,111,116,108,97,121, -0,99,117,98,101,114,101,115,0,100,101,112,116,104,0,114,101,99,97,108,99,0,108,97,115,116,115,105,122,101,0,110, -111,105,115,101,115,105,122,101,0,116,117,114,98,117,108,0,98,114,105,103,104,116,0,99,111,110,116,114,97,115,116,0, -114,102,97,99,0,103,102,97,99,0,98,102,97,99,0,102,105,108,116,101,114,115,105,122,101,0,109,103,95,72,0,109, -103,95,108,97,99,117,110,97,114,105,116,121,0,109,103,95,111,99,116,97,118,101,115,0,109,103,95,111,102,102,115,101, -116,0,109,103,95,103,97,105,110,0,100,105,115,116,95,97,109,111,117,110,116,0,110,115,95,111,117,116,115,99,97,108, -101,0,118,110,95,119,49,0,118,110,95,119,50,0,118,110,95,119,51,0,118,110,95,119,52,0,118,110,95,109,101,120, -112,0,118,110,95,100,105,115,116,109,0,118,110,95,99,111,108,116,121,112,101,0,110,111,105,115,101,100,101,112,116,104, -0,110,111,105,115,101,116,121,112,101,0,110,111,105,115,101,98,97,115,105,115,0,110,111,105,115,101,98,97,115,105,115, -50,0,105,109,97,102,108,97,103,0,99,114,111,112,120,109,105,110,0,99,114,111,112,121,109,105,110,0,99,114,111,112, -120,109,97,120,0,99,114,111,112,121,109,97,120,0,120,114,101,112,101,97,116,0,121,114,101,112,101,97,116,0,101,120, -116,101,110,100,0,99,104,101,99,107,101,114,100,105,115,116,0,110,97,98,108,97,0,105,117,115,101,114,0,42,110,111, -100,101,116,114,101,101,0,42,112,108,117,103,105,110,0,42,99,111,98,97,0,42,101,110,118,0,117,115,101,95,110,111, -100,101,115,0,112,97,100,91,55,93,0,108,111,99,91,51,93,0,114,111,116,91,51,93,0,109,97,116,91,52,93,91, -52,93,0,109,105,110,91,51,93,0,109,97,120,91,51,93,0,112,97,100,51,0,109,111,100,101,0,116,111,116,101,120, -0,115,104,100,119,114,0,115,104,100,119,103,0,115,104,100,119,98,0,115,104,100,119,112,97,100,0,101,110,101,114,103, -121,0,100,105,115,116,0,115,112,111,116,115,105,122,101,0,115,112,111,116,98,108,101,110,100,0,104,97,105,110,116,0, -97,116,116,49,0,97,116,116,50,0,42,99,117,114,102,97,108,108,111,102,102,0,102,97,108,108,111,102,102,95,116,121, -112,101,0,115,104,97,100,115,112,111,116,115,105,122,101,0,98,105,97,115,0,115,111,102,116,0,98,117,102,115,105,122, -101,0,115,97,109,112,0,98,117,102,102,101,114,115,0,102,105,108,116,101,114,116,121,112,101,0,98,117,102,102,108,97, -103,0,98,117,102,116,121,112,101,0,114,97,121,95,115,97,109,112,0,114,97,121,95,115,97,109,112,121,0,114,97,121, -95,115,97,109,112,122,0,114,97,121,95,115,97,109,112,95,116,121,112,101,0,97,114,101,97,95,115,104,97,112,101,0, -97,114,101,97,95,115,105,122,101,0,97,114,101,97,95,115,105,122,101,121,0,97,114,101,97,95,115,105,122,101,122,0, -97,100,97,112,116,95,116,104,114,101,115,104,0,114,97,121,95,115,97,109,112,95,109,101,116,104,111,100,0,116,101,120, -97,99,116,0,115,104,97,100,104,97,108,111,115,116,101,112,0,115,117,110,95,101,102,102,101,99,116,95,116,121,112,101, -0,115,107,121,98,108,101,110,100,116,121,112,101,0,104,111,114,105,122,111,110,95,98,114,105,103,104,116,110,101,115,115, -0,115,112,114,101,97,100,0,115,117,110,95,98,114,105,103,104,116,110,101,115,115,0,115,117,110,95,115,105,122,101,0, -98,97,99,107,115,99,97,116,116,101,114,101,100,95,108,105,103,104,116,0,115,117,110,95,105,110,116,101,110,115,105,116, -121,0,97,116,109,95,116,117,114,98,105,100,105,116,121,0,97,116,109,95,105,110,115,99,97,116,116,101,114,105,110,103, -95,102,97,99,116,111,114,0,97,116,109,95,101,120,116,105,110,99,116,105,111,110,95,102,97,99,116,111,114,0,97,116, -109,95,100,105,115,116,97,110,99,101,95,102,97,99,116,111,114,0,115,107,121,98,108,101,110,100,102,97,99,0,115,107, -121,95,101,120,112,111,115,117,114,101,0,115,107,121,95,99,111,108,111,114,115,112,97,99,101,0,112,97,100,52,0,89, -70,95,110,117,109,112,104,111,116,111,110,115,0,89,70,95,110,117,109,115,101,97,114,99,104,0,89,70,95,112,104,100, -101,112,116,104,0,89,70,95,117,115,101,113,109,99,0,89,70,95,98,117,102,115,105,122,101,0,89,70,95,112,97,100, -0,89,70,95,99,97,117,115,116,105,99,98,108,117,114,0,89,70,95,108,116,114,97,100,105,117,115,0,89,70,95,103, -108,111,119,105,110,116,0,89,70,95,103,108,111,119,111,102,115,0,89,70,95,103,108,111,119,116,121,112,101,0,89,70, -95,112,97,100,50,0,42,109,116,101,120,91,49,56,93,0,115,112,101,99,114,0,115,112,101,99,103,0,115,112,101,99, -98,0,109,105,114,114,0,109,105,114,103,0,109,105,114,98,0,97,109,98,114,0,97,109,98,98,0,97,109,98,103,0, -97,109,98,0,101,109,105,116,0,97,110,103,0,115,112,101,99,116,114,97,0,114,97,121,95,109,105,114,114,111,114,0, -97,108,112,104,97,0,114,101,102,0,115,112,101,99,0,122,111,102,102,115,0,97,100,100,0,116,114,97,110,115,108,117, -99,101,110,99,121,0,102,114,101,115,110,101,108,95,109,105,114,0,102,114,101,115,110,101,108,95,109,105,114,95,105,0, -102,114,101,115,110,101,108,95,116,114,97,0,102,114,101,115,110,101,108,95,116,114,97,95,105,0,102,105,108,116,101,114, -0,116,120,95,108,105,109,105,116,0,116,120,95,102,97,108,108,111,102,102,0,114,97,121,95,100,101,112,116,104,0,114, -97,121,95,100,101,112,116,104,95,116,114,97,0,104,97,114,0,115,101,101,100,49,0,115,101,101,100,50,0,103,108,111, -115,115,95,109,105,114,0,103,108,111,115,115,95,116,114,97,0,115,97,109,112,95,103,108,111,115,115,95,109,105,114,0, -115,97,109,112,95,103,108,111,115,115,95,116,114,97,0,97,100,97,112,116,95,116,104,114,101,115,104,95,109,105,114,0, -97,100,97,112,116,95,116,104,114,101,115,104,95,116,114,97,0,97,110,105,115,111,95,103,108,111,115,115,95,109,105,114, -0,100,105,115,116,95,109,105,114,0,102,97,100,101,116,111,95,109,105,114,0,115,104,97,100,101,95,102,108,97,103,0, -109,111,100,101,95,108,0,102,108,97,114,101,99,0,115,116,97,114,99,0,108,105,110,101,99,0,114,105,110,103,99,0, -104,97,115,105,122,101,0,102,108,97,114,101,115,105,122,101,0,115,117,98,115,105,122,101,0,102,108,97,114,101,98,111, -111,115,116,0,115,116,114,97,110,100,95,115,116,97,0,115,116,114,97,110,100,95,101,110,100,0,115,116,114,97,110,100, -95,101,97,115,101,0,115,116,114,97,110,100,95,115,117,114,102,110,111,114,0,115,116,114,97,110,100,95,109,105,110,0, -115,116,114,97,110,100,95,119,105,100,116,104,102,97,100,101,0,115,116,114,97,110,100,95,117,118,110,97,109,101,91,51, -50,93,0,115,98,105,97,115,0,108,98,105,97,115,0,115,104,97,100,95,97,108,112,104,97,0,115,101,112,116,101,120, -0,114,103,98,115,101,108,0,112,114,95,116,121,112,101,0,112,114,95,98,97,99,107,0,112,114,95,108,97,109,112,0, -109,108,95,102,108,97,103,0,100,105,102,102,95,115,104,97,100,101,114,0,115,112,101,99,95,115,104,97,100,101,114,0, -114,111,117,103,104,110,101,115,115,0,114,101,102,114,97,99,0,112,97,114,97,109,91,52,93,0,114,109,115,0,100,97, -114,107,110,101,115,115,0,42,114,97,109,112,95,99,111,108,0,42,114,97,109,112,95,115,112,101,99,0,114,97,109,112, -105,110,95,99,111,108,0,114,97,109,112,105,110,95,115,112,101,99,0,114,97,109,112,98,108,101,110,100,95,99,111,108, -0,114,97,109,112,98,108,101,110,100,95,115,112,101,99,0,114,97,109,112,95,115,104,111,119,0,114,97,109,112,102,97, -99,95,99,111,108,0,114,97,109,112,102,97,99,95,115,112,101,99,0,42,103,114,111,117,112,0,102,114,105,99,116,105, -111,110,0,102,104,0,114,101,102,108,101,99,116,0,102,104,100,105,115,116,0,120,121,102,114,105,99,116,0,100,121,110, -97,109,111,100,101,0,115,115,115,95,114,97,100,105,117,115,91,51,93,0,115,115,115,95,99,111,108,91,51,93,0,115, -115,115,95,101,114,114,111,114,0,115,115,115,95,115,99,97,108,101,0,115,115,115,95,105,111,114,0,115,115,115,95,99, -111,108,102,97,99,0,115,115,115,95,116,101,120,102,97,99,0,115,115,115,95,102,114,111,110,116,0,115,115,115,95,98, -97,99,107,0,115,115,115,95,102,108,97,103,0,115,115,115,95,112,114,101,115,101,116,0,89,70,95,97,114,0,89,70, -95,97,103,0,89,70,95,97,98,0,89,70,95,100,115,99,97,108,101,0,89,70,95,100,112,119,114,0,89,70,95,100, -115,109,112,0,89,70,95,112,114,101,115,101,116,0,89,70,95,100,106,105,116,0,103,112,117,109,97,116,101,114,105,97, -108,0,110,97,109,101,91,50,53,54,93,0,115,99,97,108,101,0,42,98,98,0,105,49,0,106,49,0,107,49,0,105, -50,0,106,50,0,107,50,0,115,101,108,99,111,108,49,0,115,101,108,99,111,108,50,0,113,117,97,116,91,52,93,0, -101,120,112,120,0,101,120,112,121,0,101,120,112,122,0,114,97,100,0,114,97,100,50,0,115,0,42,109,97,116,0,42, -105,109,97,116,0,101,108,101,109,115,0,100,105,115,112,0,42,42,109,97,116,0,116,111,116,99,111,108,0,119,105,114, -101,115,105,122,101,0,114,101,110,100,101,114,115,105,122,101,0,116,104,114,101,115,104,0,118,101,99,91,51,93,91,51, -93,0,97,108,102,97,0,119,101,105,103,104,116,0,114,97,100,105,117,115,0,104,49,0,104,50,0,102,49,0,102,50, -0,102,51,0,104,105,100,101,0,118,101,99,91,52,93,0,109,97,116,95,110,114,0,112,110,116,115,117,0,112,110,116, -115,118,0,114,101,115,111,108,117,0,114,101,115,111,108,118,0,111,114,100,101,114,117,0,111,114,100,101,114,118,0,102, -108,97,103,117,0,102,108,97,103,118,0,42,107,110,111,116,115,117,0,42,107,110,111,116,115,118,0,116,105,108,116,95, -105,110,116,101,114,112,0,114,97,100,105,117,115,95,105,110,116,101,114,112,0,99,104,97,114,105,100,120,0,107,101,114, -110,0,104,0,110,117,114,98,0,42,98,101,118,111,98,106,0,42,116,97,112,101,114,111,98,106,0,42,116,101,120,116, -111,110,99,117,114,118,101,0,42,112,97,116,104,0,42,107,101,121,0,98,101,118,0,112,97,116,104,108,101,110,0,98, -101,118,114,101,115,111,108,0,119,105,100,116,104,0,101,120,116,49,0,101,120,116,50,0,114,101,115,111,108,117,95,114, -101,110,0,114,101,115,111,108,118,95,114,101,110,0,115,112,97,99,101,109,111,100,101,0,115,112,97,99,105,110,103,0, -108,105,110,101,100,105,115,116,0,115,104,101,97,114,0,102,115,105,122,101,0,119,111,114,100,115,112,97,99,101,0,117, -108,112,111,115,0,117,108,104,101,105,103,104,116,0,120,111,102,0,121,111,102,0,108,105,110,101,119,105,100,116,104,0, -42,115,116,114,0,102,97,109,105,108,121,91,50,52,93,0,42,118,102,111,110,116,0,42,118,102,111,110,116,98,0,42, -118,102,111,110,116,105,0,42,118,102,111,110,116,98,105,0,115,101,112,99,104,97,114,0,116,111,116,98,111,120,0,97, -99,116,98,111,120,0,42,116,98,0,115,101,108,115,116,97,114,116,0,115,101,108,101,110,100,0,42,115,116,114,105,110, -102,111,0,99,117,114,105,110,102,111,0,101,102,102,101,99,116,0,42,109,102,97,99,101,0,42,109,116,102,97,99,101, -0,42,116,102,97,99,101,0,42,109,118,101,114,116,0,42,109,101,100,103,101,0,42,100,118,101,114,116,0,42,109,99, -111,108,0,42,109,115,116,105,99,107,121,0,42,116,101,120,99,111,109,101,115,104,0,42,109,115,101,108,101,99,116,0, -118,100,97,116,97,0,101,100,97,116,97,0,102,100,97,116,97,0,116,111,116,101,100,103,101,0,116,111,116,102,97,99, -101,0,116,111,116,115,101,108,101,99,116,0,97,99,116,95,102,97,99,101,0,99,117,98,101,109,97,112,115,105,122,101, -0,115,109,111,111,116,104,114,101,115,104,0,115,117,98,100,105,118,0,115,117,98,100,105,118,114,0,115,117,98,115,117, -114,102,116,121,112,101,0,42,109,114,0,42,112,118,0,42,116,112,97,103,101,0,117,118,91,52,93,91,50,93,0,99, -111,108,91,52,93,0,116,114,97,110,115,112,0,116,105,108,101,0,117,110,119,114,97,112,0,118,49,0,118,50,0,118, -51,0,118,52,0,101,100,99,111,100,101,0,99,114,101,97,115,101,0,98,119,101,105,103,104,116,0,100,101,102,95,110, -114,0,42,100,119,0,116,111,116,119,101,105,103,104,116,0,99,111,91,51,93,0,110,111,91,51,93,0,112,97,100,91, -51,93,0,117,118,91,50,93,0,99,111,91,50,93,0,105,110,100,101,120,0,102,0,105,0,115,91,50,53,54,93,0, -118,91,52,93,0,109,105,100,0,118,91,50,93,0,42,102,97,99,101,115,0,42,99,111,108,102,97,99,101,115,0,42, -101,100,103,101,115,0,42,101,100,103,101,95,98,111,117,110,100,97,114,121,95,115,116,97,116,101,115,0,42,118,101,114, -116,95,101,100,103,101,95,109,97,112,0,42,118,101,114,116,95,102,97,99,101,95,109,97,112,0,42,109,97,112,95,109, -101,109,0,42,118,101,114,116,115,0,108,101,118,101,108,115,0,108,101,118,101,108,95,99,111,117,110,116,0,99,117,114, -114,101,110,116,0,110,101,119,108,118,108,0,101,100,103,101,108,118,108,0,112,105,110,108,118,108,0,114,101,110,100,101, -114,108,118,108,0,117,115,101,95,99,111,108,0,42,101,100,103,101,95,102,108,97,103,115,0,42,101,100,103,101,95,99, -114,101,97,115,101,115,0,42,118,101,114,116,95,109,97,112,0,42,101,100,103,101,95,109,97,112,0,42,111,108,100,95, -102,97,99,101,115,0,42,111,108,100,95,101,100,103,101,115,0,42,101,114,114,111,114,0,109,111,100,105,102,105,101,114, -0,115,117,98,100,105,118,84,121,112,101,0,114,101,110,100,101,114,76,101,118,101,108,115,0,42,101,109,67,97,99,104, -101,0,42,109,67,97,99,104,101,0,100,101,102,97,120,105,115,0,112,97,100,91,54,93,0,108,101,110,103,116,104,0, -114,97,110,100,111,109,105,122,101,0,115,101,101,100,0,42,111,98,95,97,114,109,0,42,115,116,97,114,116,95,99,97, -112,0,42,101,110,100,95,99,97,112,0,42,99,117,114,118,101,95,111,98,0,42,111,102,102,115,101,116,95,111,98,0, -111,102,102,115,101,116,91,51,93,0,115,99,97,108,101,91,51,93,0,109,101,114,103,101,95,100,105,115,116,0,102,105, -116,95,116,121,112,101,0,111,102,102,115,101,116,95,116,121,112,101,0,99,111,117,110,116,0,97,120,105,115,0,116,111, -108,101,114,97,110,99,101,0,42,109,105,114,114,111,114,95,111,98,0,115,112,108,105,116,95,97,110,103,108,101,0,118, -97,108,117,101,0,114,101,115,0,118,97,108,95,102,108,97,103,115,0,108,105,109,95,102,108,97,103,115,0,101,95,102, -108,97,103,115,0,98,101,118,101,108,95,97,110,103,108,101,0,100,101,102,103,114,112,95,110,97,109,101,91,51,50,93, -0,42,116,101,120,116,117,114,101,0,115,116,114,101,110,103,116,104,0,100,105,114,101,99,116,105,111,110,0,109,105,100, -108,101,118,101,108,0,116,101,120,109,97,112,112,105,110,103,0,42,109,97,112,95,111,98,106,101,99,116,0,117,118,108, -97,121,101,114,95,110,97,109,101,91,51,50,93,0,117,118,108,97,121,101,114,95,116,109,112,0,42,112,114,111,106,101, -99,116,111,114,115,91,49,48,93,0,42,105,109,97,103,101,0,110,117,109,95,112,114,111,106,101,99,116,111,114,115,0, -97,115,112,101,99,116,120,0,97,115,112,101,99,116,121,0,112,101,114,99,101,110,116,0,102,97,99,101,67,111,117,110, -116,0,102,97,99,0,114,101,112,101,97,116,0,42,111,98,106,101,99,116,99,101,110,116,101,114,0,115,116,97,114,116, -120,0,115,116,97,114,116,121,0,104,101,105,103,104,116,0,110,97,114,114,111,119,0,115,112,101,101,100,0,100,97,109, -112,0,102,97,108,108,111,102,102,0,116,105,109,101,111,102,102,115,0,108,105,102,101,116,105,109,101,0,100,101,102,111, -114,109,102,108,97,103,0,109,117,108,116,105,0,42,112,114,101,118,67,111,115,0,112,97,114,101,110,116,105,110,118,91, -52,93,91,52,93,0,99,101,110,116,91,51,93,0,42,105,110,100,101,120,97,114,0,116,111,116,105,110,100,101,120,0, -102,111,114,99,101,0,42,99,108,111,116,104,79,98,106,101,99,116,0,42,115,105,109,95,112,97,114,109,115,0,42,99, -111,108,108,95,112,97,114,109,115,0,42,112,111,105,110,116,95,99,97,99,104,101,0,42,120,0,42,120,110,101,119,0, -42,120,111,108,100,0,42,99,117,114,114,101,110,116,95,120,110,101,119,0,42,99,117,114,114,101,110,116,95,120,0,42, -99,117,114,114,101,110,116,95,118,0,42,109,102,97,99,101,115,0,110,117,109,118,101,114,116,115,0,110,117,109,102,97, -99,101,115,0,97,98,115,111,114,112,116,105,111,110,0,116,105,109,101,0,42,98,118,104,116,114,101,101,0,42,100,109, -0,111,112,101,114,97,116,105,111,110,0,118,101,114,116,101,120,0,116,111,116,105,110,102,108,117,101,110,99,101,0,103, -114,105,100,115,105,122,101,0,110,101,101,100,98,105,110,100,0,42,98,105,110,100,119,101,105,103,104,116,115,0,42,98, -105,110,100,99,111,115,0,116,111,116,99,97,103,101,118,101,114,116,0,42,100,121,110,103,114,105,100,0,42,100,121,110, -105,110,102,108,117,101,110,99,101,115,0,42,100,121,110,118,101,114,116,115,0,42,112,97,100,50,0,100,121,110,103,114, -105,100,115,105,122,101,0,100,121,110,99,101,108,108,109,105,110,91,51,93,0,100,121,110,99,101,108,108,119,105,100,116, -104,0,98,105,110,100,109,97,116,91,52,93,91,52,93,0,42,112,115,121,115,0,116,111,116,100,109,118,101,114,116,0, -116,111,116,100,109,101,100,103,101,0,116,111,116,100,109,102,97,99,101,0,112,115,121,115,0,114,116,91,50,93,0,42, -102,97,99,101,112,97,0,118,103,114,111,117,112,0,112,114,111,116,101,99,116,0,42,102,115,115,0,42,116,97,114,103, -101,116,0,42,97,117,120,84,97,114,103,101,116,0,118,103,114,111,117,112,95,110,97,109,101,91,51,50,93,0,107,101, -101,112,68,105,115,116,0,115,104,114,105,110,107,84,121,112,101,0,115,104,114,105,110,107,79,112,116,115,0,112,114,111, -106,65,120,105,115,0,115,117,98,115,117,114,102,76,101,118,101,108,115,0,42,111,114,105,103,105,110,0,102,97,99,116, -111,114,0,108,105,109,105,116,91,50,93,0,111,114,105,103,105,110,79,112,116,115,0,112,110,116,115,119,0,111,112,110, -116,115,117,0,111,112,110,116,115,118,0,111,112,110,116,115,119,0,116,121,112,101,117,0,116,121,112,101,118,0,116,121, -112,101,119,0,102,117,0,102,118,0,102,119,0,100,117,0,100,118,0,100,119,0,42,100,101,102,0,118,101,99,91,56, -93,91,51,93,0,112,97,114,116,121,112,101,0,112,97,114,49,0,112,97,114,50,0,112,97,114,51,0,112,97,114,115, -117,98,115,116,114,91,51,50,93,0,42,116,114,97,99,107,0,42,112,114,111,120,121,0,42,112,114,111,120,121,95,103, -114,111,117,112,0,42,112,114,111,120,121,95,102,114,111,109,0,42,97,99,116,105,111,110,0,42,112,111,115,101,108,105, -98,0,42,112,111,115,101,0,99,111,110,115,116,114,97,105,110,116,67,104,97,110,110,101,108,115,0,100,101,102,98,97, -115,101,0,109,111,100,105,102,105,101,114,115,0,100,108,111,99,91,51,93,0,111,114,105,103,91,51,93,0,100,115,105, -122,101,91,51,93,0,100,114,111,116,91,51,93,0,111,98,109,97,116,91,52,93,91,52,93,0,99,111,110,115,116,105, -110,118,91,52,93,91,52,93,0,108,97,121,0,99,111,108,98,105,116,115,0,116,114,97,110,115,102,108,97,103,0,105, -112,111,102,108,97,103,0,116,114,97,99,107,102,108,97,103,0,117,112,102,108,97,103,0,110,108,97,102,108,97,103,0, -112,114,111,116,101,99,116,102,108,97,103,0,105,112,111,119,105,110,0,115,99,97,102,108,97,103,0,115,99,97,118,105, -115,102,108,97,103,0,98,111,117,110,100,116,121,112,101,0,100,117,112,111,110,0,100,117,112,111,102,102,0,100,117,112, -115,116,97,0,100,117,112,101,110,100,0,115,102,0,99,116,105,109,101,0,109,97,115,115,0,100,97,109,112,105,110,103, -0,105,110,101,114,116,105,97,0,102,111,114,109,102,97,99,116,111,114,0,114,100,97,109,112,105,110,103,0,115,105,122, -101,102,97,99,0,109,97,114,103,105,110,0,109,97,120,95,118,101,108,0,109,105,110,95,118,101,108,0,109,95,99,111, -110,116,97,99,116,80,114,111,99,101,115,115,105,110,103,84,104,114,101,115,104,111,108,100,0,100,116,0,100,116,120,0, -97,99,116,99,111,108,0,101,109,112,116,121,95,100,114,97,119,116,121,112,101,0,112,97,100,49,91,51,93,0,101,109, -112,116,121,95,100,114,97,119,115,105,122,101,0,100,117,112,102,97,99,101,115,99,97,0,112,114,111,112,0,115,101,110, -115,111,114,115,0,99,111,110,116,114,111,108,108,101,114,115,0,97,99,116,117,97,116,111,114,115,0,98,98,115,105,122, -101,91,51,93,0,97,99,116,100,101,102,0,103,97,109,101,102,108,97,103,0,103,97,109,101,102,108,97,103,50,0,42, -98,115,111,102,116,0,115,111,102,116,102,108,97,103,0,97,110,105,115,111,116,114,111,112,105,99,70,114,105,99,116,105, -111,110,91,51,93,0,99,111,110,115,116,114,97,105,110,116,115,0,110,108,97,115,116,114,105,112,115,0,104,111,111,107, -115,0,112,97,114,116,105,99,108,101,115,121,115,116,101,109,0,42,112,100,0,42,115,111,102,116,0,42,100,117,112,95, -103,114,111,117,112,0,102,108,117,105,100,115,105,109,70,108,97,103,0,114,101,115,116,114,105,99,116,102,108,97,103,0, -115,104,97,112,101,110,114,0,115,104,97,112,101,102,108,97,103,0,114,101,99,97,108,99,111,0,98,111,100,121,95,116, -121,112,101,0,42,102,108,117,105,100,115,105,109,83,101,116,116,105,110,103,115,0,42,100,101,114,105,118,101,100,68,101, -102,111,114,109,0,42,100,101,114,105,118,101,100,70,105,110,97,108,0,108,97,115,116,68,97,116,97,77,97,115,107,0, -115,116,97,116,101,0,105,110,105,116,95,115,116,97,116,101,0,103,112,117,108,97,109,112,0,99,117,114,105,110,100,101, -120,0,97,99,116,105,118,101,0,100,101,102,108,101,99,116,0,102,111,114,99,101,102,105,101,108,100,0,112,100,101,102, -95,100,97,109,112,0,112,100,101,102,95,114,100,97,109,112,0,112,100,101,102,95,112,101,114,109,0,112,100,101,102,95, -102,114,105,99,116,0,112,100,101,102,95,114,102,114,105,99,116,0,102,95,115,116,114,101,110,103,116,104,0,102,95,112, -111,119,101,114,0,102,95,100,105,115,116,0,102,95,100,97,109,112,0,109,97,120,100,105,115,116,0,109,105,110,100,105, -115,116,0,109,97,120,114,97,100,0,109,105,110,114,97,100,0,102,95,112,111,119,101,114,95,114,0,112,100,101,102,95, -115,98,100,97,109,112,0,112,100,101,102,95,115,98,105,102,116,0,112,100,101,102,95,115,98,111,102,116,0,99,108,117, -109,112,95,102,97,99,0,99,108,117,109,112,95,112,111,119,0,107,105,110,107,95,102,114,101,113,0,107,105,110,107,95, -115,104,97,112,101,0,107,105,110,107,95,97,109,112,0,102,114,101,101,95,101,110,100,0,116,101,120,95,110,97,98,108, -97,0,116,101,120,95,109,111,100,101,0,107,105,110,107,0,107,105,110,107,95,97,120,105,115,0,114,116,50,0,42,114, -110,103,0,102,95,110,111,105,115,101,0,115,105,109,102,114,97,109,101,0,115,116,97,114,116,102,114,97,109,101,0,101, -110,100,102,114,97,109,101,0,101,100,105,116,102,114,97,109,101,0,108,105,110,83,116,105,102,102,0,97,110,103,83,116, -105,102,102,0,118,111,108,117,109,101,0,118,105,116,101,114,97,116,105,111,110,115,0,112,105,116,101,114,97,116,105,111, -110,115,0,100,105,116,101,114,97,116,105,111,110,115,0,99,105,116,101,114,97,116,105,111,110,115,0,107,83,82,72,82, -95,67,76,0,107,83,75,72,82,95,67,76,0,107,83,83,72,82,95,67,76,0,107,83,82,95,83,80,76,84,95,67, -76,0,107,83,75,95,83,80,76,84,95,67,76,0,107,83,83,95,83,80,76,84,95,67,76,0,107,86,67,70,0,107, -68,80,0,107,68,71,0,107,76,70,0,107,80,82,0,107,86,67,0,107,68,70,0,107,77,84,0,107,67,72,82,0, -107,75,72,82,0,107,83,72,82,0,107,65,72,82,0,99,111,108,108,105,115,105,111,110,102,108,97,103,115,0,110,117, -109,99,108,117,115,116,101,114,105,116,101,114,97,116,105,111,110,115,0,119,101,108,100,105,110,103,0,42,112,97,114,116, -105,99,108,101,115,0,116,111,116,112,111,105,110,116,0,116,111,116,115,112,114,105,110,103,0,42,98,112,111,105,110,116, -0,42,98,115,112,114,105,110,103,0,109,115,103,95,108,111,99,107,0,109,115,103,95,118,97,108,117,101,0,110,111,100, -101,109,97,115,115,0,110,97,109,101,100,86,71,95,77,97,115,115,91,51,50,93,0,103,114,97,118,0,109,101,100,105, -97,102,114,105,99,116,0,114,107,108,105,109,105,116,0,112,104,121,115,105,99,115,95,115,112,101,101,100,0,103,111,97, -108,115,112,114,105,110,103,0,103,111,97,108,102,114,105,99,116,0,109,105,110,103,111,97,108,0,109,97,120,103,111,97, -108,0,100,101,102,103,111,97,108,0,118,101,114,116,103,114,111,117,112,0,110,97,109,101,100,86,71,95,83,111,102,116, -103,111,97,108,91,51,50,93,0,102,117,122,122,121,110,101,115,115,0,105,110,115,112,114,105,110,103,0,105,110,102,114, -105,99,116,0,110,97,109,101,100,86,71,95,83,112,114,105,110,103,95,75,91,51,50,93,0,101,102,114,97,0,105,110, -116,101,114,118,97,108,0,108,111,99,97,108,0,115,111,108,118,101,114,102,108,97,103,115,0,42,42,107,101,121,115,0, -116,111,116,112,111,105,110,116,107,101,121,0,115,101,99,111,110,100,115,112,114,105,110,103,0,99,111,108,98,97,108,108, -0,98,97,108,108,100,97,109,112,0,98,97,108,108,115,116,105,102,102,0,115,98,99,95,109,111,100,101,0,97,101,114, -111,101,100,103,101,0,109,105,110,108,111,111,112,115,0,109,97,120,108,111,111,112,115,0,99,104,111,107,101,0,115,111, -108,118,101,114,95,73,68,0,112,108,97,115,116,105,99,0,115,112,114,105,110,103,112,114,101,108,111,97,100,0,42,115, -99,114,97,116,99,104,0,115,104,101,97,114,115,116,105,102,102,0,105,110,112,117,115,104,0,42,112,111,105,110,116,99, -97,99,104,101,0,115,104,111,119,95,97,100,118,97,110,99,101,100,111,112,116,105,111,110,115,0,114,101,115,111,108,117, -116,105,111,110,120,121,122,0,112,114,101,118,105,101,119,114,101,115,120,121,122,0,114,101,97,108,115,105,122,101,0,103, -117,105,68,105,115,112,108,97,121,77,111,100,101,0,114,101,110,100,101,114,68,105,115,112,108,97,121,77,111,100,101,0, -118,105,115,99,111,115,105,116,121,86,97,108,117,101,0,118,105,115,99,111,115,105,116,121,77,111,100,101,0,118,105,115, -99,111,115,105,116,121,69,120,112,111,110,101,110,116,0,103,114,97,118,120,0,103,114,97,118,121,0,103,114,97,118,122, -0,97,110,105,109,83,116,97,114,116,0,97,110,105,109,69,110,100,0,103,115,116,97,114,0,109,97,120,82,101,102,105, -110,101,0,105,110,105,86,101,108,120,0,105,110,105,86,101,108,121,0,105,110,105,86,101,108,122,0,42,111,114,103,77, -101,115,104,0,42,109,101,115,104,83,117,114,102,97,99,101,0,42,109,101,115,104,66,66,0,115,117,114,102,100,97,116, -97,80,97,116,104,91,50,52,48,93,0,98,98,83,116,97,114,116,91,51,93,0,98,98,83,105,122,101,91,51,93,0, -116,121,112,101,70,108,97,103,115,0,100,111,109,97,105,110,78,111,118,101,99,103,101,110,0,118,111,108,117,109,101,73, -110,105,116,84,121,112,101,0,112,97,114,116,83,108,105,112,86,97,108,117,101,0,103,101,110,101,114,97,116,101,84,114, -97,99,101,114,115,0,103,101,110,101,114,97,116,101,80,97,114,116,105,99,108,101,115,0,115,117,114,102,97,99,101,83, -109,111,111,116,104,105,110,103,0,115,117,114,102,97,99,101,83,117,98,100,105,118,115,0,112,97,114,116,105,99,108,101, -73,110,102,83,105,122,101,0,112,97,114,116,105,99,108,101,73,110,102,65,108,112,104,97,0,102,97,114,70,105,101,108, -100,83,105,122,101,0,42,109,101,115,104,83,117,114,102,78,111,114,109,97,108,115,0,99,112,115,84,105,109,101,83,116, -97,114,116,0,99,112,115,84,105,109,101,69,110,100,0,99,112,115,81,117,97,108,105,116,121,0,97,116,116,114,97,99, -116,102,111,114,99,101,83,116,114,101,110,103,116,104,0,97,116,116,114,97,99,116,102,111,114,99,101,82,97,100,105,117, -115,0,118,101,108,111,99,105,116,121,102,111,114,99,101,83,116,114,101,110,103,116,104,0,118,101,108,111,99,105,116,121, -102,111,114,99,101,82,97,100,105,117,115,0,108,97,115,116,103,111,111,100,102,114,97,109,101,0,109,105,115,116,121,112, -101,0,104,111,114,114,0,104,111,114,103,0,104,111,114,98,0,104,111,114,107,0,122,101,110,114,0,122,101,110,103,0, -122,101,110,98,0,122,101,110,107,0,97,109,98,107,0,102,97,115,116,99,111,108,0,101,120,112,111,115,117,114,101,0, -101,120,112,0,114,97,110,103,101,0,108,105,110,102,97,99,0,108,111,103,102,97,99,0,103,114,97,118,105,116,121,0, -97,99,116,105,118,105,116,121,66,111,120,82,97,100,105,117,115,0,115,107,121,116,121,112,101,0,111,99,99,108,117,115, -105,111,110,82,101,115,0,112,104,121,115,105,99,115,69,110,103,105,110,101,0,116,105,99,114,97,116,101,0,109,97,120, -108,111,103,105,99,115,116,101,112,0,112,104,121,115,117,98,115,116,101,112,0,109,97,120,112,104,121,115,116,101,112,0, -109,105,115,105,0,109,105,115,116,115,116,97,0,109,105,115,116,100,105,115,116,0,109,105,115,116,104,105,0,115,116,97, -114,114,0,115,116,97,114,103,0,115,116,97,114,98,0,115,116,97,114,107,0,115,116,97,114,115,105,122,101,0,115,116, -97,114,109,105,110,100,105,115,116,0,115,116,97,114,100,105,115,116,0,115,116,97,114,99,111,108,110,111,105,115,101,0, -100,111,102,115,116,97,0,100,111,102,101,110,100,0,100,111,102,109,105,110,0,100,111,102,109,97,120,0,97,111,100,105, -115,116,0,97,111,100,105,115,116,102,97,99,0,97,111,101,110,101,114,103,121,0,97,111,98,105,97,115,0,97,111,109, -111,100,101,0,97,111,115,97,109,112,0,97,111,109,105,120,0,97,111,99,111,108,111,114,0,97,111,95,97,100,97,112, -116,95,116,104,114,101,115,104,0,97,111,95,97,100,97,112,116,95,115,112,101,101,100,95,102,97,99,0,97,111,95,97, -112,112,114,111,120,95,101,114,114,111,114,0,97,111,95,97,112,112,114,111,120,95,99,111,114,114,101,99,116,105,111,110, -0,97,111,95,115,97,109,112,95,109,101,116,104,111,100,0,97,111,95,103,97,116,104,101,114,95,109,101,116,104,111,100, -0,97,111,95,97,112,112,114,111,120,95,112,97,115,115,101,115,0,42,97,111,115,112,104,101,114,101,0,42,97,111,116, -97,98,108,101,115,0,104,101,109,105,114,101,115,0,109,97,120,105,116,101,114,0,100,114,97,119,116,121,112,101,0,115, -117,98,115,104,111,111,116,112,0,115,117,98,115,104,111,111,116,101,0,110,111,100,101,108,105,109,0,109,97,120,115,117, -98,108,97,109,112,0,112,97,109,97,0,112,97,109,105,0,101,108,109,97,0,101,108,109,105,0,109,97,120,110,111,100, -101,0,99,111,110,118,101,114,103,101,110,99,101,0,114,97,100,102,97,99,0,103,97,109,109,97,0,115,101,108,99,111, -108,0,115,120,0,115,121,0,42,108,112,70,111,114,109,97,116,0,42,108,112,80,97,114,109,115,0,99,98,70,111,114, -109,97,116,0,99,98,80,97,114,109,115,0,102,99,99,84,121,112,101,0,102,99,99,72,97,110,100,108,101,114,0,100, -119,75,101,121,70,114,97,109,101,69,118,101,114,121,0,100,119,81,117,97,108,105,116,121,0,100,119,66,121,116,101,115, -80,101,114,83,101,99,111,110,100,0,100,119,70,108,97,103,115,0,100,119,73,110,116,101,114,108,101,97,118,101,69,118, -101,114,121,0,97,118,105,99,111,100,101,99,110,97,109,101,91,49,50,56,93,0,42,99,100,80,97,114,109,115,0,42, -112,97,100,0,99,100,83,105,122,101,0,113,116,99,111,100,101,99,110,97,109,101,91,49,50,56,93,0,99,111,100,101, -99,0,97,117,100,105,111,95,99,111,100,101,99,0,118,105,100,101,111,95,98,105,116,114,97,116,101,0,97,117,100,105, -111,95,98,105,116,114,97,116,101,0,103,111,112,95,115,105,122,101,0,114,99,95,109,105,110,95,114,97,116,101,0,114, -99,95,109,97,120,95,114,97,116,101,0,114,99,95,98,117,102,102,101,114,95,115,105,122,101,0,109,117,120,95,112,97, -99,107,101,116,95,115,105,122,101,0,109,117,120,95,114,97,116,101,0,109,105,120,114,97,116,101,0,109,97,105,110,0, -42,109,97,116,95,111,118,101,114,114,105,100,101,0,42,108,105,103,104,116,95,111,118,101,114,114,105,100,101,0,108,97, -121,95,122,109,97,115,107,0,108,97,121,102,108,97,103,0,112,97,115,115,102,108,97,103,0,112,97,115,115,95,120,111, -114,0,42,97,118,105,99,111,100,101,99,100,97,116,97,0,42,113,116,99,111,100,101,99,100,97,116,97,0,102,102,99, -111,100,101,99,100,97,116,97,0,99,102,114,97,0,112,115,102,114,97,0,112,101,102,114,97,0,105,109,97,103,101,115, -0,102,114,97,109,97,112,116,111,0,116,104,114,101,97,100,115,0,102,114,97,109,101,108,101,110,0,98,108,117,114,102, -97,99,0,101,100,103,101,82,0,101,100,103,101,71,0,101,100,103,101,66,0,102,117,108,108,115,99,114,101,101,110,0, -120,112,108,97,121,0,121,112,108,97,121,0,102,114,101,113,112,108,97,121,0,97,116,116,114,105,98,0,114,116,49,0, -115,116,101,114,101,111,109,111,100,101,0,100,105,109,101,110,115,105,111,110,115,112,114,101,115,101,116,0,109,97,120,105, -109,115,105,122,101,0,120,115,99,104,0,121,115,99,104,0,120,112,97,114,116,115,0,121,112,97,114,116,115,0,119,105, -110,112,111,115,0,112,108,97,110,101,115,0,105,109,116,121,112,101,0,115,117,98,105,109,116,121,112,101,0,113,117,97, -108,105,116,121,0,114,112,97,100,0,114,112,97,100,49,0,114,112,97,100,50,0,115,99,101,109,111,100,101,0,114,101, -110,100,101,114,101,114,0,111,99,114,101,115,0,97,108,112,104,97,109,111,100,101,0,111,115,97,0,102,114,115,95,115, -101,99,0,101,100,103,101,105,110,116,0,115,97,102,101,116,121,0,98,111,114,100,101,114,0,100,105,115,112,114,101,99, -116,0,108,97,121,101,114,115,0,97,99,116,108,97,121,0,120,97,115,112,0,121,97,115,112,0,102,114,115,95,115,101, -99,95,98,97,115,101,0,103,97,117,115,115,0,112,111,115,116,109,117,108,0,112,111,115,116,103,97,109,109,97,0,112, -111,115,116,104,117,101,0,112,111,115,116,115,97,116,0,100,105,116,104,101,114,95,105,110,116,101,110,115,105,116,121,0, -98,97,107,101,95,111,115,97,0,98,97,107,101,95,102,105,108,116,101,114,0,98,97,107,101,95,109,111,100,101,0,98, -97,107,101,95,102,108,97,103,0,98,97,107,101,95,110,111,114,109,97,108,95,115,112,97,99,101,0,98,97,107,101,95, -113,117,97,100,95,115,112,108,105,116,0,98,97,107,101,95,109,97,120,100,105,115,116,0,98,97,107,101,95,98,105,97, -115,100,105,115,116,0,98,97,107,101,95,112,97,100,0,71,73,113,117,97,108,105,116,121,0,71,73,99,97,99,104,101, -0,71,73,109,101,116,104,111,100,0,71,73,112,104,111,116,111,110,115,0,71,73,100,105,114,101,99,116,0,89,70,95, -65,65,0,89,70,101,120,112,111,114,116,120,109,108,0,89,70,95,110,111,98,117,109,112,0,89,70,95,99,108,97,109, -112,114,103,98,0,121,102,112,97,100,49,0,71,73,100,101,112,116,104,0,71,73,99,97,117,115,100,101,112,116,104,0, -71,73,112,105,120,101,108,115,112,101,114,115,97,109,112,108,101,0,71,73,112,104,111,116,111,110,99,111,117,110,116,0, -71,73,109,105,120,112,104,111,116,111,110,115,0,71,73,112,104,111,116,111,110,114,97,100,105,117,115,0,89,70,95,114, -97,121,100,101,112,116,104,0,89,70,95,65,65,112,97,115,115,101,115,0,89,70,95,65,65,115,97,109,112,108,101,115, -0,121,102,112,97,100,50,0,71,73,115,104,97,100,111,119,113,117,97,108,105,116,121,0,71,73,114,101,102,105,110,101, -109,101,110,116,0,71,73,112,111,119,101,114,0,71,73,105,110,100,105,114,112,111,119,101,114,0,89,70,95,103,97,109, -109,97,0,89,70,95,101,120,112,111,115,117,114,101,0,89,70,95,114,97,121,98,105,97,115,0,89,70,95,65,65,112, -105,120,101,108,115,105,122,101,0,89,70,95,65,65,116,104,114,101,115,104,111,108,100,0,98,97,99,107,98,117,102,91, -49,54,48,93,0,112,105,99,91,49,54,48,93,0,115,116,97,109,112,0,115,116,97,109,112,95,102,111,110,116,95,105, -100,0,115,116,97,109,112,95,117,100,97,116,97,91,49,54,48,93,0,102,103,95,115,116,97,109,112,91,52,93,0,98, -103,95,115,116,97,109,112,91,52,93,0,115,105,109,112,108,105,102,121,95,115,117,98,115,117,114,102,0,115,105,109,112, -108,105,102,121,95,115,104,97,100,111,119,115,97,109,112,108,101,115,0,115,105,109,112,108,105,102,121,95,112,97,114,116, -105,99,108,101,115,0,115,105,109,112,108,105,102,121,95,97,111,115,115,115,0,99,105,110,101,111,110,119,104,105,116,101, -0,99,105,110,101,111,110,98,108,97,99,107,0,99,105,110,101,111,110,103,97,109,109,97,0,106,112,50,95,112,114,101, -115,101,116,0,106,112,50,95,100,101,112,116,104,0,114,112,97,100,51,0,100,111,109,101,114,101,115,0,100,111,109,101, -109,111,100,101,0,100,111,109,101,97,110,103,108,101,0,100,111,109,101,116,105,108,116,0,100,111,109,101,114,101,115,98, -117,102,0,42,100,111,109,101,116,101,120,116,0,112,97,114,116,105,99,108,101,95,112,101,114,99,0,115,117,98,115,117, -114,102,95,109,97,120,0,115,104,97,100,98,117,102,115,97,109,112,108,101,95,109,97,120,0,97,111,95,101,114,114,111, -114,0,99,111,108,91,51,93,0,102,114,97,109,101,0,110,97,109,101,91,54,52,93,0,42,98,114,117,115,104,0,116, -111,111,108,0,115,101,97,109,95,98,108,101,101,100,0,110,111,114,109,97,108,95,97,110,103,108,101,0,115,116,101,112, -0,105,110,118,101,114,116,0,116,111,116,114,101,107,101,121,0,116,111,116,97,100,100,107,101,121,0,98,114,117,115,104, -116,121,112,101,0,98,114,117,115,104,91,55,93,0,101,109,105,116,116,101,114,100,105,115,116,0,100,114,97,119,95,116, -105,109,101,100,0,110,97,109,101,91,51,54,93,0,109,97,116,91,51,93,91,51,93,0,99,111,114,110,101,114,116,121, -112,101,0,101,100,105,116,98,117,116,102,108,97,103,0,106,111,105,110,116,114,105,108,105,109,105,116,0,100,101,103,114, -0,116,117,114,110,0,101,120,116,114,95,111,102,102,115,0,100,111,117,98,108,105,109,105,116,0,115,101,103,109,101,110, -116,115,0,114,105,110,103,115,0,118,101,114,116,105,99,101,115,0,117,110,119,114,97,112,112,101,114,0,117,118,99,97, -108,99,95,114,97,100,105,117,115,0,117,118,99,97,108,99,95,99,117,98,101,115,105,122,101,0,117,118,99,97,108,99, -95,109,97,114,103,105,110,0,117,118,99,97,108,99,95,109,97,112,100,105,114,0,117,118,99,97,108,99,95,109,97,112, -97,108,105,103,110,0,117,118,99,97,108,99,95,102,108,97,103,0,97,117,116,111,105,107,95,99,104,97,105,110,108,101, -110,0,105,109,97,112,97,105,110,116,0,112,97,114,116,105,99,108,101,0,115,101,108,101,99,116,95,116,104,114,101,115, -104,0,99,108,101,97,110,95,116,104,114,101,115,104,0,114,101,116,111,112,111,95,109,111,100,101,0,114,101,116,111,112, -111,95,112,97,105,110,116,95,116,111,111,108,0,108,105,110,101,95,100,105,118,0,101,108,108,105,112,115,101,95,100,105, -118,0,114,101,116,111,112,111,95,104,111,116,115,112,111,116,0,109,117,108,116,105,114,101,115,95,115,117,98,100,105,118, -95,116,121,112,101,0,115,107,103,101,110,95,114,101,115,111,108,117,116,105,111,110,0,115,107,103,101,110,95,116,104,114, -101,115,104,111,108,100,95,105,110,116,101,114,110,97,108,0,115,107,103,101,110,95,116,104,114,101,115,104,111,108,100,95, -101,120,116,101,114,110,97,108,0,115,107,103,101,110,95,108,101,110,103,116,104,95,114,97,116,105,111,0,115,107,103,101, -110,95,108,101,110,103,116,104,95,108,105,109,105,116,0,115,107,103,101,110,95,97,110,103,108,101,95,108,105,109,105,116, -0,115,107,103,101,110,95,99,111,114,114,101,108,97,116,105,111,110,95,108,105,109,105,116,0,115,107,103,101,110,95,115, -121,109,109,101,116,114,121,95,108,105,109,105,116,0,115,107,103,101,110,95,114,101,116,97,114,103,101,116,95,97,110,103, -108,101,95,119,101,105,103,104,116,0,115,107,103,101,110,95,114,101,116,97,114,103,101,116,95,108,101,110,103,116,104,95, -119,101,105,103,104,116,0,115,107,103,101,110,95,114,101,116,97,114,103,101,116,95,100,105,115,116,97,110,99,101,95,119, -101,105,103,104,116,0,115,107,103,101,110,95,111,112,116,105,111,110,115,0,115,107,103,101,110,95,112,111,115,116,112,114, -111,0,115,107,103,101,110,95,112,111,115,116,112,114,111,95,112,97,115,115,101,115,0,115,107,103,101,110,95,115,117,98, -100,105,118,105,115,105,111,110,115,91,51,93,0,115,107,103,101,110,95,109,117,108,116,105,95,108,101,118,101,108,0,42, -115,107,103,101,110,95,116,101,109,112,108,97,116,101,0,98,111,110,101,95,115,107,101,116,99,104,105,110,103,0,98,111, -110,101,95,115,107,101,116,99,104,105,110,103,95,99,111,110,118,101,114,116,0,115,107,103,101,110,95,115,117,98,100,105, -118,105,115,105,111,110,95,110,117,109,98,101,114,0,115,107,103,101,110,95,114,101,116,97,114,103,101,116,95,111,112,116, -105,111,110,115,0,115,107,103,101,110,95,114,101,116,97,114,103,101,116,95,114,111,108,108,0,115,107,103,101,110,95,115, -105,100,101,95,115,116,114,105,110,103,91,56,93,0,115,107,103,101,110,95,110,117,109,95,115,116,114,105,110,103,91,56, -93,0,101,100,103,101,95,109,111,100,101,0,112,97,100,51,91,50,93,0,100,105,114,0,118,105,101,119,0,42,115,101, -115,115,105,111,110,0,42,99,117,109,97,112,0,100,114,97,119,98,114,117,115,104,0,115,109,111,111,116,104,98,114,117, -115,104,0,112,105,110,99,104,98,114,117,115,104,0,105,110,102,108,97,116,101,98,114,117,115,104,0,103,114,97,98,98, -114,117,115,104,0,108,97,121,101,114,98,114,117,115,104,0,102,108,97,116,116,101,110,98,114,117,115,104,0,112,105,118, -111,116,91,51,93,0,98,114,117,115,104,95,116,121,112,101,0,116,101,120,110,114,0,116,101,120,114,101,112,116,0,116, -101,120,102,97,100,101,0,116,101,120,115,101,112,0,97,118,101,114,97,103,105,110,103,0,116,97,98,108,101,116,95,115, -105,122,101,0,116,97,98,108,101,116,95,115,116,114,101,110,103,116,104,0,115,121,109,109,0,114,97,107,101,0,97,120, -105,115,108,111,99,107,0,42,99,97,109,101,114,97,0,42,119,111,114,108,100,0,42,115,101,116,0,98,97,115,101,0, -42,98,97,115,97,99,116,0,99,117,114,115,111,114,91,51,93,0,116,119,99,101,110,116,91,51,93,0,116,119,109,105, -110,91,51,93,0,116,119,109,97,120,91,51,93,0,101,100,105,116,98,117,116,115,105,122,101,0,115,101,108,101,99,116, -109,111,100,101,0,112,114,111,112,111,114,116,105,111,110,97,108,0,112,114,111,112,95,109,111,100,101,0,97,117,116,111, -109,101,114,103,101,0,112,97,100,53,0,112,97,100,54,0,97,117,116,111,107,101,121,95,109,111,100,101,0,42,101,100, -0,42,114,97,100,105,111,0,102,114,97,109,105,110,103,0,42,116,111,111,108,115,101,116,116,105,110,103,115,0,97,117, -100,105,111,0,116,114,97,110,115,102,111,114,109,95,115,112,97,99,101,115,0,106,117,109,112,102,114,97,109,101,0,115, -110,97,112,95,109,111,100,101,0,115,110,97,112,95,102,108,97,103,0,115,110,97,112,95,116,97,114,103,101,116,0,42, -116,104,101,68,97,103,0,100,97,103,105,115,118,97,108,105,100,0,100,97,103,102,108,97,103,115,0,115,99,117,108,112, -116,100,97,116,97,0,102,114,97,109,101,95,115,116,101,112,0,122,111,111,109,0,98,108,101,110,100,0,120,105,109,0, -121,105,109,0,115,112,97,99,101,116,121,112,101,0,98,108,111,99,107,115,99,97,108,101,0,42,97,114,101,97,0,98, -108,111,99,107,104,97,110,100,108,101,114,91,56,93,0,118,105,101,119,109,97,116,91,52,93,91,52,93,0,118,105,101, -119,105,110,118,91,52,93,91,52,93,0,112,101,114,115,109,97,116,91,52,93,91,52,93,0,112,101,114,115,105,110,118, -91,52,93,91,52,93,0,119,105,110,109,97,116,49,91,52,93,91,52,93,0,118,105,101,119,109,97,116,49,91,52,93, -91,52,93,0,118,105,101,119,113,117,97,116,91,52,93,0,122,102,97,99,0,108,97,121,95,117,115,101,100,0,112,101, -114,115,112,0,42,111,98,95,99,101,110,116,114,101,0,42,98,103,112,105,99,0,42,108,111,99,97,108,118,100,0,42, -114,105,0,42,114,101,116,111,112,111,95,118,105,101,119,95,100,97,116,97,0,42,100,101,112,116,104,115,0,111,98,95, -99,101,110,116,114,101,95,98,111,110,101,91,51,50,93,0,108,111,99,97,108,118,105,101,119,0,108,97,121,97,99,116, -0,115,99,101,110,101,108,111,99,107,0,97,114,111,117,110,100,0,99,97,109,122,111,111,109,0,112,105,118,111,116,95, -108,97,115,116,0,103,114,105,100,0,103,114,105,100,118,105,101,119,0,112,105,120,115,105,122,101,0,110,101,97,114,0, -102,97,114,0,99,97,109,100,120,0,99,97,109,100,121,0,103,114,105,100,108,105,110,101,115,0,118,105,101,119,98,117, -116,0,103,114,105,100,102,108,97,103,0,109,111,100,101,115,101,108,101,99,116,0,116,119,116,121,112,101,0,116,119,109, -111,100,101,0,116,119,102,108,97,103,0,116,119,100,114,97,119,102,108,97,103,0,116,119,109,97,116,91,52,93,91,52, -93,0,99,108,105,112,91,52,93,91,52,93,0,42,99,108,105,112,98,98,0,97,102,116,101,114,100,114,97,119,0,122, -98,117,102,0,120,114,97,121,0,102,108,97,103,50,0,103,114,105,100,115,117,98,100,105,118,0,107,101,121,102,108,97, -103,115,0,110,100,111,102,109,111,100,101,0,110,100,111,102,102,105,108,116,101,114,0,42,112,114,111,112,101,114,116,105, -101,115,95,115,116,111,114,97,103,101,0,42,103,112,100,0,108,118,105,101,119,113,117,97,116,91,52,93,0,108,112,101, -114,115,112,0,108,118,105,101,119,0,118,101,114,116,0,104,111,114,0,109,97,115,107,0,109,105,110,91,50,93,0,109, -97,120,91,50,93,0,109,105,110,122,111,111,109,0,109,97,120,122,111,111,109,0,115,99,114,111,108,108,0,107,101,101, -112,116,111,116,0,107,101,101,112,97,115,112,101,99,116,0,107,101,101,112,122,111,111,109,0,111,108,100,119,105,110,120, -0,111,108,100,119,105,110,121,0,99,117,114,115,111,114,91,50,93,0,114,111,119,98,117,116,0,118,50,100,0,42,101, -100,105,116,105,112,111,0,105,112,111,107,101,121,0,97,99,116,110,97,109,101,91,51,50,93,0,99,111,110,115,116,110, -97,109,101,91,51,50,93,0,98,111,110,101,110,97,109,101,91,51,50,93,0,116,111,116,105,112,111,0,112,105,110,0, -98,117,116,111,102,115,0,99,104,97,110,110,101,108,0,108,111,99,107,0,109,101,100,105,97,110,91,51,93,0,99,117, -114,115,101,110,115,0,99,117,114,97,99,116,0,97,108,105,103,110,0,116,97,98,111,0,109,97,105,110,98,0,109,97, -105,110,98,111,0,42,108,111,99,107,112,111,105,110,0,116,101,120,102,114,111,109,0,115,104,111,119,103,114,111,117,112, -0,109,111,100,101,108,116,121,112,101,0,115,99,114,105,112,116,98,108,111,99,107,0,114,101,95,97,108,105,103,110,0, -111,108,100,107,101,121,112,114,101,115,115,0,116,97,98,91,55,93,0,114,101,110,100,101,114,95,115,105,122,101,0,99, -104,97,110,115,104,111,119,110,0,122,101,98,114,97,0,42,102,105,108,101,108,105,115,116,0,116,111,116,102,105,108,101, -0,116,105,116,108,101,91,50,52,93,0,100,105,114,91,50,52,48,93,0,102,105,108,101,91,56,48,93,0,111,102,115, -0,115,111,114,116,0,109,97,120,110,97,109,101,108,101,110,0,99,111,108,108,117,109,115,0,102,95,102,112,0,102,112, -95,115,116,114,91,56,93,0,42,108,105,98,102,105,108,101,100,97,116,97,0,114,101,116,118,97,108,0,109,101,110,117, -0,97,99,116,0,40,42,114,101,116,117,114,110,102,117,110,99,41,40,41,0,40,42,114,101,116,117,114,110,102,117,110, -99,95,101,118,101,110,116,41,40,41,0,40,42,114,101,116,117,114,110,102,117,110,99,95,97,114,103,115,41,40,41,0, -42,97,114,103,49,0,42,97,114,103,50,0,42,109,101,110,117,112,0,42,112,117,112,109,101,110,117,0,111,111,112,115, -0,118,105,115,105,102,108,97,103,0,116,114,101,101,0,42,116,114,101,101,115,116,111,114,101,0,115,101,97,114,99,104, -95,115,116,114,105,110,103,91,51,50,93,0,115,101,97,114,99,104,95,116,115,101,0,115,101,97,114,99,104,95,102,108, -97,103,115,0,100,111,95,0,111,117,116,108,105,110,101,118,105,115,0,115,116,111,114,101,102,108,97,103,0,100,101,112, -115,95,102,108,97,103,115,0,105,109,97,110,114,0,99,117,114,116,105,108,101,0,105,109,116,121,112,101,110,114,0,100, -116,95,117,118,0,115,116,105,99,107,121,0,100,116,95,117,118,115,116,114,101,116,99,104,0,112,97,100,91,53,93,0, -99,101,110,116,120,0,99,101,110,116,121,0,97,117,116,111,115,110,97,112,0,42,116,101,120,116,0,116,111,112,0,118, -105,101,119,108,105,110,101,115,0,102,111,110,116,95,105,100,0,108,104,101,105,103,104,116,0,108,101,102,116,0,115,104, -111,119,108,105,110,101,110,114,115,0,116,97,98,110,117,109,98,101,114,0,99,117,114,114,116,97,98,95,115,101,116,0, -115,104,111,119,115,121,110,116,97,120,0,111,118,101,114,119,114,105,116,101,0,112,105,120,95,112,101,114,95,108,105,110, -101,0,116,120,116,115,99,114,111,108,108,0,116,120,116,98,97,114,0,119,111,114,100,119,114,97,112,0,100,111,112,108, -117,103,105,110,115,0,42,112,121,95,100,114,97,119,0,42,112,121,95,101,118,101,110,116,0,42,112,121,95,98,117,116, -116,111,110,0,42,112,121,95,98,114,111,119,115,101,114,99,97,108,108,98,97,99,107,0,42,112,121,95,103,108,111,98, -97,108,100,105,99,116,0,108,97,115,116,115,112,97,99,101,0,115,99,114,105,112,116,110,97,109,101,91,50,53,54,93, -0,115,99,114,105,112,116,97,114,103,91,50,53,54,93,0,42,115,99,114,105,112,116,0,42,98,117,116,95,114,101,102, -115,0,114,101,100,114,97,119,115,0,42,105,100,0,97,115,112,101,99,116,0,42,99,117,114,102,111,110,116,0,42,101, -100,105,116,116,114,101,101,0,116,114,101,101,116,121,112,101,0,42,102,105,108,101,115,0,97,99,116,105,118,101,95,102, -105,108,101,0,110,117,109,116,105,108,101,115,120,0,110,117,109,116,105,108,101,115,121,0,115,101,108,115,116,97,116,101, -0,118,105,101,119,114,101,99,116,0,98,111,111,107,109,97,114,107,114,101,99,116,0,115,99,114,111,108,108,112,111,115, -0,115,99,114,111,108,108,104,101,105,103,104,116,0,115,99,114,111,108,108,97,114,101,97,0,97,99,116,105,118,101,95, -98,111,111,107,109,97,114,107,0,112,114,118,95,119,0,112,114,118,95,104,0,42,105,109,103,0,111,117,116,108,105,110, -101,91,52,93,0,110,101,117,116,114,97,108,91,52,93,0,97,99,116,105,111,110,91,52,93,0,115,101,116,116,105,110, -103,91,52,93,0,115,101,116,116,105,110,103,49,91,52,93,0,115,101,116,116,105,110,103,50,91,52,93,0,110,117,109, -91,52,93,0,116,101,120,116,102,105,101,108,100,91,52,93,0,116,101,120,116,102,105,101,108,100,95,104,105,91,52,93, -0,112,111,112,117,112,91,52,93,0,116,101,120,116,91,52,93,0,116,101,120,116,95,104,105,91,52,93,0,109,101,110, -117,95,98,97,99,107,91,52,93,0,109,101,110,117,95,105,116,101,109,91,52,93,0,109,101,110,117,95,104,105,108,105, -116,101,91,52,93,0,109,101,110,117,95,116,101,120,116,91,52,93,0,109,101,110,117,95,116,101,120,116,95,104,105,91, -52,93,0,98,117,116,95,100,114,97,119,116,121,112,101,0,105,99,111,110,102,105,108,101,91,56,48,93,0,98,97,99, -107,91,52,93,0,104,101,97,100,101,114,91,52,93,0,112,97,110,101,108,91,52,93,0,115,104,97,100,101,49,91,52, -93,0,115,104,97,100,101,50,91,52,93,0,104,105,108,105,116,101,91,52,93,0,103,114,105,100,91,52,93,0,119,105, -114,101,91,52,93,0,115,101,108,101,99,116,91,52,93,0,108,97,109,112,91,52,93,0,97,99,116,105,118,101,91,52, -93,0,103,114,111,117,112,91,52,93,0,103,114,111,117,112,95,97,99,116,105,118,101,91,52,93,0,116,114,97,110,115, -102,111,114,109,91,52,93,0,118,101,114,116,101,120,91,52,93,0,118,101,114,116,101,120,95,115,101,108,101,99,116,91, -52,93,0,101,100,103,101,91,52,93,0,101,100,103,101,95,115,101,108,101,99,116,91,52,93,0,101,100,103,101,95,115, -101,97,109,91,52,93,0,101,100,103,101,95,115,104,97,114,112,91,52,93,0,101,100,103,101,95,102,97,99,101,115,101, -108,91,52,93,0,102,97,99,101,91,52,93,0,102,97,99,101,95,115,101,108,101,99,116,91,52,93,0,102,97,99,101, -95,100,111,116,91,52,93,0,110,111,114,109,97,108,91,52,93,0,98,111,110,101,95,115,111,108,105,100,91,52,93,0, -98,111,110,101,95,112,111,115,101,91,52,93,0,115,116,114,105,112,91,52,93,0,115,116,114,105,112,95,115,101,108,101, -99,116,91,52,93,0,99,102,114,97,109,101,91,52,93,0,118,101,114,116,101,120,95,115,105,122,101,0,102,97,99,101, -100,111,116,95,115,105,122,101,0,98,112,97,100,91,50,93,0,115,121,110,116,97,120,108,91,52,93,0,115,121,110,116, -97,120,110,91,52,93,0,115,121,110,116,97,120,98,91,52,93,0,115,121,110,116,97,120,118,91,52,93,0,115,121,110, -116,97,120,99,91,52,93,0,109,111,118,105,101,91,52,93,0,105,109,97,103,101,91,52,93,0,115,99,101,110,101,91, -52,93,0,97,117,100,105,111,91,52,93,0,101,102,102,101,99,116,91,52,93,0,112,108,117,103,105,110,91,52,93,0, -116,114,97,110,115,105,116,105,111,110,91,52,93,0,109,101,116,97,91,52,93,0,101,100,105,116,109,101,115,104,95,97, -99,116,105,118,101,91,52,93,0,104,97,110,100,108,101,95,118,101,114,116,101,120,91,52,93,0,104,97,110,100,108,101, -95,118,101,114,116,101,120,95,115,101,108,101,99,116,91,52,93,0,104,97,110,100,108,101,95,118,101,114,116,101,120,95, -115,105,122,101,0,104,112,97,100,91,55,93,0,115,111,108,105,100,91,52,93,0,116,117,105,0,116,98,117,116,115,0, -116,118,51,100,0,116,102,105,108,101,0,116,105,112,111,0,116,105,110,102,111,0,116,115,110,100,0,116,97,99,116,0, -116,110,108,97,0,116,115,101,113,0,116,105,109,97,0,116,105,109,97,115,101,108,0,116,101,120,116,0,116,111,111,112, -115,0,116,116,105,109,101,0,116,110,111,100,101,0,116,97,114,109,91,50,48,93,0,98,112,97,100,91,52,93,0,98, -112,97,100,49,91,52,93,0,115,112,101,99,91,52,93,0,100,117,112,102,108,97,103,0,115,97,118,101,116,105,109,101, -0,116,101,109,112,100,105,114,91,49,54,48,93,0,102,111,110,116,100,105,114,91,49,54,48,93,0,114,101,110,100,101, -114,100,105,114,91,49,54,48,93,0,116,101,120,116,117,100,105,114,91,49,54,48,93,0,112,108,117,103,116,101,120,100, -105,114,91,49,54,48,93,0,112,108,117,103,115,101,113,100,105,114,91,49,54,48,93,0,112,121,116,104,111,110,100,105, -114,91,49,54,48,93,0,115,111,117,110,100,100,105,114,91,49,54,48,93,0,121,102,101,120,112,111,114,116,100,105,114, -91,49,54,48,93,0,118,101,114,115,105,111,110,115,0,118,114,109,108,102,108,97,103,0,103,97,109,101,102,108,97,103, -115,0,119,104,101,101,108,108,105,110,101,115,99,114,111,108,108,0,117,105,102,108,97,103,0,108,97,110,103,117,97,103, -101,0,117,115,101,114,112,114,101,102,0,118,105,101,119,122,111,111,109,0,99,111,110,115,111,108,101,95,98,117,102,102, -101,114,0,99,111,110,115,111,108,101,95,111,117,116,0,109,105,120,98,117,102,115,105,122,101,0,102,111,110,116,115,105, -122,101,0,101,110,99,111,100,105,110,103,0,116,114,97,110,115,111,112,116,115,0,109,101,110,117,116,104,114,101,115,104, -111,108,100,49,0,109,101,110,117,116,104,114,101,115,104,111,108,100,50,0,102,111,110,116,110,97,109,101,91,50,53,54, -93,0,116,104,101,109,101,115,0,117,110,100,111,115,116,101,112,115,0,117,110,100,111,109,101,109,111,114,121,0,103,112, -95,109,97,110,104,97,116,116,101,110,100,105,115,116,0,103,112,95,101,117,99,108,105,100,101,97,110,100,105,115,116,0, -103,112,95,101,114,97,115,101,114,0,103,112,95,115,101,116,116,105,110,103,115,0,116,98,95,108,101,102,116,109,111,117, -115,101,0,116,98,95,114,105,103,104,116,109,111,117,115,101,0,108,105,103,104,116,91,51,93,0,116,119,95,104,111,116, -115,112,111,116,0,116,119,95,102,108,97,103,0,116,119,95,104,97,110,100,108,101,115,105,122,101,0,116,119,95,115,105, -122,101,0,116,101,120,116,105,109,101,111,117,116,0,116,101,120,99,111,108,108,101,99,116,114,97,116,101,0,109,101,109, -99,97,99,104,101,108,105,109,105,116,0,112,114,101,102,101,116,99,104,102,114,97,109,101,115,0,102,114,97,109,101,115, -101,114,118,101,114,112,111,114,116,0,112,97,100,95,114,111,116,95,97,110,103,108,101,0,111,98,99,101,110,116,101,114, -95,100,105,97,0,114,118,105,115,105,122,101,0,114,118,105,98,114,105,103,104,116,0,114,101,99,101,110,116,95,102,105, -108,101,115,0,115,109,111,111,116,104,95,118,105,101,119,116,120,0,103,108,114,101,115,108,105,109,105,116,0,110,100,111, -102,95,112,97,110,0,110,100,111,102,95,114,111,116,97,116,101,0,99,117,114,115,115,105,122,101,0,112,97,100,91,56, -93,0,118,101,114,115,101,109,97,115,116,101,114,91,49,54,48,93,0,118,101,114,115,101,117,115,101,114,91,49,54,48, -93,0,103,108,97,108,112,104,97,99,108,105,112,0,97,117,116,111,107,101,121,95,102,108,97,103,0,99,111,98,97,95, -119,101,105,103,104,116,0,118,101,114,116,98,97,115,101,0,101,100,103,101,98,97,115,101,0,97,114,101,97,98,97,115, -101,0,42,115,99,101,110,101,0,101,110,100,120,0,101,110,100,121,0,115,105,122,101,120,0,115,105,122,101,121,0,115, -99,101,110,101,110,114,0,115,99,114,101,101,110,110,114,0,102,117,108,108,0,109,97,105,110,119,105,110,0,119,105,110, -97,107,116,0,104,97,110,100,108,101,114,91,56,93,0,42,110,101,119,118,0,118,101,99,0,42,118,49,0,42,118,50, -0,112,97,110,101,108,110,97,109,101,91,54,52,93,0,116,97,98,110,97,109,101,91,54,52,93,0,100,114,97,119,110, -97,109,101,91,54,52,93,0,111,102,115,120,0,111,102,115,121,0,99,111,110,116,114,111,108,0,115,110,97,112,0,111, -108,100,95,111,102,115,120,0,111,108,100,95,111,102,115,121,0,115,111,114,116,99,111,117,110,116,101,114,0,42,112,97, -110,101,108,116,97,98,0,42,118,51,0,42,118,52,0,42,102,117,108,108,0,119,105,110,109,97,116,91,52,93,91,52, -93,0,104,101,97,100,114,99,116,0,119,105,110,114,99,116,0,104,101,97,100,119,105,110,0,119,105,110,0,104,101,97, -100,101,114,116,121,112,101,0,98,117,116,115,112,97,99,101,116,121,112,101,0,119,105,110,120,0,119,105,110,121,0,104, -101,97,100,95,115,119,97,112,0,104,101,97,100,95,101,113,117,97,108,0,119,105,110,95,115,119,97,112,0,119,105,110, -95,101,113,117,97,108,0,104,101,97,100,98,117,116,108,101,110,0,104,101,97,100,98,117,116,111,102,115,0,99,117,114, -115,111,114,0,115,112,97,99,101,100,97,116,97,0,117,105,98,108,111,99,107,115,0,112,97,110,101,108,115,0,115,117, -98,118,115,116,114,91,52,93,0,115,117,98,118,101,114,115,105,111,110,0,112,97,100,115,0,109,105,110,118,101,114,115, -105,111,110,0,109,105,110,115,117,98,118,101,114,115,105,111,110,0,100,105,115,112,108,97,121,109,111,100,101,0,42,99, -117,114,115,99,114,101,101,110,0,42,99,117,114,115,99,101,110,101,0,102,105,108,101,102,108,97,103,115,0,103,108,111, -98,97,108,102,0,110,97,109,101,91,56,48,93,0,42,105,98,117,102,0,42,105,98,117,102,95,99,111,109,112,0,42, -115,101,49,0,42,115,101,50,0,42,115,101,51,0,110,114,0,98,111,116,116,111,109,0,114,105,103,104,116,0,120,111, -102,115,0,121,111,102,115,0,108,105,102,116,91,51,93,0,103,97,109,109,97,91,51,93,0,103,97,105,110,91,51,93, -0,115,97,116,117,114,97,116,105,111,110,0,42,103,117,105,0,100,105,114,91,49,54,48,93,0,100,111,110,101,0,115, -116,97,114,116,115,116,105,108,108,0,101,110,100,115,116,105,108,108,0,42,115,116,114,105,112,100,97,116,97,0,111,114, -120,0,111,114,121,0,42,99,114,111,112,0,42,116,114,97,110,115,102,111,114,109,0,42,99,111,108,111,114,95,98,97, -108,97,110,99,101,0,42,116,115,116,114,105,112,100,97,116,97,0,42,116,115,116,114,105,112,100,97,116,97,95,115,116, -97,114,116,115,116,105,108,108,0,42,116,115,116,114,105,112,100,97,116,97,95,101,110,100,115,116,105,108,108,0,42,105, -98,117,102,95,115,116,97,114,116,115,116,105,108,108,0,42,105,98,117,102,95,101,110,100,115,116,105,108,108,0,42,105, -110,115,116,97,110,99,101,95,112,114,105,118,97,116,101,95,100,97,116,97,0,42,42,99,117,114,114,101,110,116,95,112, -114,105,118,97,116,101,95,100,97,116,97,0,42,116,109,112,0,115,116,97,114,116,111,102,115,0,101,110,100,111,102,115, -0,109,97,99,104,105,110,101,0,115,116,97,114,116,100,105,115,112,0,101,110,100,100,105,115,112,0,109,117,108,0,104, -97,110,100,115,105,122,101,0,97,110,105,109,95,112,114,101,115,101,101,107,0,42,115,116,114,105,112,0,102,97,99,102, -48,0,102,97,99,102,49,0,42,115,101,113,49,0,42,115,101,113,50,0,42,115,101,113,51,0,115,101,113,98,97,115, -101,0,42,115,111,117,110,100,0,42,104,100,97,117,100,105,111,0,108,101,118,101,108,0,112,97,110,0,115,116,114,111, -98,101,0,42,101,102,102,101,99,116,100,97,116,97,0,97,110,105,109,95,115,116,97,114,116,111,102,115,0,97,110,105, -109,95,101,110,100,111,102,115,0,98,108,101,110,100,95,109,111,100,101,0,98,108,101,110,100,95,111,112,97,99,105,116, -121,0,42,111,108,100,98,97,115,101,112,0,42,112,97,114,115,101,113,0,42,115,101,113,98,97,115,101,112,0,109,101, -116,97,115,116,97,99,107,0,101,100,103,101,87,105,100,116,104,0,102,111,114,119,97,114,100,0,119,105,112,101,116,121, -112,101,0,102,77,105,110,105,0,102,67,108,97,109,112,0,102,66,111,111,115,116,0,100,68,105,115,116,0,100,81,117, -97,108,105,116,121,0,98,78,111,67,111,109,112,0,83,99,97,108,101,120,73,110,105,0,83,99,97,108,101,121,73,110, -105,0,83,99,97,108,101,120,70,105,110,0,83,99,97,108,101,121,70,105,110,0,120,73,110,105,0,120,70,105,110,0, -121,73,110,105,0,121,70,105,110,0,114,111,116,73,110,105,0,114,111,116,70,105,110,0,105,110,116,101,114,112,111,108, -97,116,105,111,110,0,42,102,114,97,109,101,77,97,112,0,103,108,111,98,97,108,83,112,101,101,100,0,108,97,115,116, -86,97,108,105,100,70,114,97,109,101,0,98,108,101,110,100,70,114,97,109,101,115,0,98,117,116,116,121,112,101,0,117, -115,101,114,106,105,116,0,115,116,97,0,116,111,116,112,97,114,116,0,110,111,114,109,102,97,99,0,111,98,102,97,99, -0,114,97,110,100,102,97,99,0,116,101,120,102,97,99,0,114,97,110,100,108,105,102,101,0,102,111,114,99,101,91,51, -93,0,118,101,99,116,115,105,122,101,0,109,97,120,108,101,110,0,100,101,102,118,101,99,91,51,93,0,109,117,108,116, -91,52,93,0,108,105,102,101,91,52,93,0,99,104,105,108,100,91,52,93,0,109,97,116,91,52,93,0,116,101,120,109, -97,112,0,99,117,114,109,117,108,116,0,115,116,97,116,105,99,115,116,101,112,0,111,109,97,116,0,116,105,109,101,116, -101,120,0,115,112,101,101,100,116,101,120,0,102,108,97,103,50,110,101,103,0,118,101,114,116,103,114,111,117,112,95,118, -0,118,103,114,111,117,112,110,97,109,101,91,51,50,93,0,118,103,114,111,117,112,110,97,109,101,95,118,91,51,50,93, -0,42,107,101,121,115,0,109,105,110,102,97,99,0,117,115,101,100,0,117,115,101,100,101,108,101,109,0,100,120,0,100, -121,0,108,105,110,107,0,111,116,121,112,101,0,111,108,100,0,42,112,111,105,110,0,42,111,108,100,112,111,105,110,0, -114,101,115,101,116,100,105,115,116,0,108,97,115,116,118,97,108,0,42,109,97,0,107,101,121,0,113,117,97,108,0,113, -117,97,108,50,0,116,97,114,103,101,116,78,97,109,101,91,51,50,93,0,116,111,103,103,108,101,78,97,109,101,91,51, -50,93,0,118,97,108,117,101,91,51,50,93,0,109,97,120,118,97,108,117,101,91,51,50,93,0,100,101,108,97,121,0, -100,117,114,97,116,105,111,110,0,109,97,116,101,114,105,97,108,78,97,109,101,91,51,50,93,0,100,97,109,112,116,105, -109,101,114,0,112,114,111,112,110,97,109,101,91,51,50,93,0,109,97,116,110,97,109,101,91,51,50,93,0,97,120,105, -115,102,108,97,103,0,42,102,114,111,109,79,98,106,101,99,116,0,115,117,98,106,101,99,116,91,51,50,93,0,98,111, -100,121,91,51,50,93,0,112,117,108,115,101,0,102,114,101,113,0,116,111,116,108,105,110,107,115,0,42,42,108,105,110, -107,115,0,116,97,112,0,106,111,121,105,110,100,101,120,0,97,120,105,115,95,115,105,110,103,108,101,0,97,120,105,115, -102,0,98,117,116,116,111,110,0,104,97,116,0,104,97,116,102,0,112,114,101,99,105,115,105,111,110,0,115,116,114,91, -49,50,56,93,0,109,111,100,117,108,101,91,54,52,93,0,42,109,121,110,101,119,0,105,110,112,117,116,115,0,116,111, -116,115,108,105,110,107,115,0,42,42,115,108,105,110,107,115,0,118,97,108,111,0,115,116,97,116,101,95,109,97,115,107, -0,42,97,99,116,0,102,114,97,109,101,80,114,111,112,91,51,50,93,0,98,108,101,110,100,105,110,0,112,114,105,111, -114,105,116,121,0,101,110,100,95,114,101,115,101,116,0,115,116,114,105,100,101,97,120,105,115,0,115,116,114,105,100,101, -108,101,110,103,116,104,0,115,110,100,110,114,0,112,97,100,49,91,50,93,0,109,97,107,101,99,111,112,121,0,99,111, -112,121,109,97,100,101,0,112,97,100,50,91,49,93,0,116,114,97,99,107,0,42,109,101,0,108,105,110,86,101,108,111, -99,105,116,121,91,51,93,0,97,110,103,86,101,108,111,99,105,116,121,91,51,93,0,108,111,99,97,108,102,108,97,103, -0,100,121,110,95,111,112,101,114,97,116,105,111,110,0,102,111,114,99,101,108,111,99,91,51,93,0,102,111,114,99,101, -114,111,116,91,51,93,0,108,105,110,101,97,114,118,101,108,111,99,105,116,121,91,51,93,0,97,110,103,117,108,97,114, -118,101,108,111,99,105,116,121,91,51,93,0,42,114,101,102,101,114,101,110,99,101,0,98,117,116,115,116,97,0,98,117, -116,101,110,100,0,109,105,110,0,109,97,120,0,118,105,115,105,102,97,99,0,114,111,116,100,97,109,112,0,109,105,110, -108,111,99,91,51,93,0,109,97,120,108,111,99,91,51,93,0,109,105,110,114,111,116,91,51,93,0,109,97,120,114,111, -116,91,51,93,0,109,97,116,112,114,111,112,91,51,50,93,0,100,105,115,116,114,105,98,117,116,105,111,110,0,105,110, -116,95,97,114,103,95,49,0,105,110,116,95,97,114,103,95,50,0,102,108,111,97,116,95,97,114,103,95,49,0,102,108, -111,97,116,95,97,114,103,95,50,0,116,111,80,114,111,112,78,97,109,101,91,51,50,93,0,42,116,111,79,98,106,101, -99,116,0,98,111,100,121,84,121,112,101,0,102,105,108,101,110,97,109,101,91,54,52,93,0,108,111,97,100,97,110,105, -110,97,109,101,91,54,52,93,0,105,110,116,95,97,114,103,0,102,108,111,97,116,95,97,114,103,0,103,111,0,97,99, -99,101,108,108,101,114,97,116,105,111,110,0,109,97,120,115,112,101,101,100,0,109,97,120,114,111,116,115,112,101,101,100, -0,109,97,120,116,105,108,116,115,112,101,101,100,0,116,105,108,116,100,97,109,112,0,115,112,101,101,100,100,97,109,112, -0,42,115,97,109,112,108,101,0,42,115,116,114,101,97,109,0,42,110,101,119,112,97,99,107,101,100,102,105,108,101,0, -42,115,110,100,95,115,111,117,110,100,0,112,97,110,110,105,110,103,0,97,116,116,101,110,117,97,116,105,111,110,0,112, -105,116,99,104,0,109,105,110,95,103,97,105,110,0,109,97,120,95,103,97,105,110,0,100,105,115,116,97,110,99,101,0, -115,116,114,101,97,109,108,101,110,0,99,104,97,110,110,101,108,115,0,104,105,103,104,112,114,105,111,0,112,97,100,91, -49,48,93,0,103,97,105,110,0,100,111,112,112,108,101,114,102,97,99,116,111,114,0,100,111,112,112,108,101,114,118,101, -108,111,99,105,116,121,0,110,117,109,115,111,117,110,100,115,98,108,101,110,100,101,114,0,110,117,109,115,111,117,110,100, -115,103,97,109,101,101,110,103,105,110,101,0,42,108,97,109,112,114,101,110,0,103,111,98,106,101,99,116,0,100,117,112, -108,105,95,111,102,115,91,51,93,0,99,104,105,108,100,98,97,115,101,0,114,111,108,108,0,104,101,97,100,91,51,93, -0,116,97,105,108,91,51,93,0,98,111,110,101,95,109,97,116,91,51,93,91,51,93,0,97,114,109,95,104,101,97,100, -91,51,93,0,97,114,109,95,116,97,105,108,91,51,93,0,97,114,109,95,109,97,116,91,52,93,91,52,93,0,120,119, -105,100,116,104,0,122,119,105,100,116,104,0,101,97,115,101,49,0,101,97,115,101,50,0,114,97,100,95,104,101,97,100, -0,114,97,100,95,116,97,105,108,0,98,111,110,101,98,97,115,101,0,99,104,97,105,110,98,97,115,101,0,112,97,116, -104,102,108,97,103,0,108,97,121,101,114,95,112,114,111,116,101,99,116,101,100,0,103,104,111,115,116,101,112,0,103,104, -111,115,116,115,105,122,101,0,103,104,111,115,116,116,121,112,101,0,112,97,116,104,115,105,122,101,0,103,104,111,115,116, -115,102,0,103,104,111,115,116,101,102,0,112,97,116,104,115,102,0,112,97,116,104,101,102,0,112,97,116,104,98,99,0, -112,97,116,104,97,99,0,99,111,110,115,116,102,108,97,103,0,105,107,102,108,97,103,0,115,101,108,101,99,116,102,108, -97,103,0,97,103,114,112,95,105,110,100,101,120,0,42,98,111,110,101,0,42,99,104,105,108,100,0,105,107,116,114,101, -101,0,42,98,95,98,111,110,101,95,109,97,116,115,0,42,100,117,97,108,95,113,117,97,116,0,42,98,95,98,111,110, -101,95,100,117,97,108,95,113,117,97,116,115,0,99,104,97,110,95,109,97,116,91,52,93,91,52,93,0,112,111,115,101, -95,109,97,116,91,52,93,91,52,93,0,112,111,115,101,95,104,101,97,100,91,51,93,0,112,111,115,101,95,116,97,105, -108,91,51,93,0,108,105,109,105,116,109,105,110,91,51,93,0,108,105,109,105,116,109,97,120,91,51,93,0,115,116,105, -102,102,110,101,115,115,91,51,93,0,105,107,115,116,114,101,116,99,104,0,42,99,117,115,116,111,109,0,99,104,97,110, -98,97,115,101,0,112,114,111,120,121,95,108,97,121,101,114,0,115,116,114,105,100,101,95,111,102,102,115,101,116,91,51, -93,0,99,121,99,108,105,99,95,111,102,102,115,101,116,91,51,93,0,97,103,114,111,117,112,115,0,97,99,116,105,118, -101,95,103,114,111,117,112,0,99,117,115,116,111,109,67,111,108,0,99,115,0,42,103,114,112,0,114,101,115,101,114,118, -101,100,49,0,103,114,111,117,112,115,0,97,99,116,105,118,101,95,109,97,114,107,101,114,0,97,99,116,110,114,0,97, -99,116,119,105,100,116,104,0,116,105,109,101,115,108,105,100,101,0,110,97,109,101,91,51,48,93,0,111,119,110,115,112, -97,99,101,0,116,97,114,115,112,97,99,101,0,101,110,102,111,114,99,101,0,104,101,97,100,116,97,105,108,0,42,116, -97,114,0,115,117,98,116,97,114,103,101,116,91,51,50,93,0,109,97,116,114,105,120,91,52,93,91,52,93,0,115,112, -97,99,101,0,42,112,114,111,112,0,116,97,114,110,117,109,0,116,97,114,103,101,116,115,0,105,116,101,114,97,116,105, -111,110,115,0,114,111,111,116,98,111,110,101,0,109,97,120,95,114,111,111,116,98,111,110,101,0,42,112,111,108,101,116, -97,114,0,112,111,108,101,115,117,98,116,97,114,103,101,116,91,51,50,93,0,112,111,108,101,97,110,103,108,101,0,111, -114,105,101,110,116,119,101,105,103,104,116,0,103,114,97,98,116,97,114,103,101,116,91,51,93,0,114,101,115,101,114,118, -101,100,50,0,109,105,110,109,97,120,102,108,97,103,0,115,116,117,99,107,0,99,97,99,104,101,91,51,93,0,108,111, -99,107,102,108,97,103,0,102,111,108,108,111,119,102,108,97,103,0,118,111,108,109,111,100,101,0,112,108,97,110,101,0, -111,114,103,108,101,110,103,116,104,0,98,117,108,103,101,0,112,105,118,88,0,112,105,118,89,0,112,105,118,90,0,97, -120,88,0,97,120,89,0,97,120,90,0,109,105,110,76,105,109,105,116,91,54,93,0,109,97,120,76,105,109,105,116,91, -54,93,0,101,120,116,114,97,70,122,0,105,110,118,109,97,116,91,52,93,91,52,93,0,102,114,111,109,0,116,111,0, -109,97,112,91,51,93,0,101,120,112,111,0,102,114,111,109,95,109,105,110,91,51,93,0,102,114,111,109,95,109,97,120, -91,51,93,0,116,111,95,109,105,110,91,51,93,0,116,111,95,109,97,120,91,51,93,0,122,109,105,110,0,122,109,97, -120,0,112,97,100,91,57,93,0,99,104,97,110,110,101,108,91,51,50,93,0,110,111,95,114,111,116,95,97,120,105,115, -0,115,116,114,105,100,101,95,97,120,105,115,0,99,117,114,109,111,100,0,97,99,116,115,116,97,114,116,0,97,99,116, -101,110,100,0,97,99,116,111,102,102,115,0,115,116,114,105,100,101,108,101,110,0,98,108,101,110,100,111,117,116,0,115, -116,114,105,100,101,99,104,97,110,110,101,108,91,51,50,93,0,111,102,102,115,95,98,111,110,101,91,51,50,93,0,104, -97,115,105,110,112,117,116,0,104,97,115,111,117,116,112,117,116,0,100,97,116,97,116,121,112,101,0,115,111,99,107,101, -116,116,121,112,101,0,42,110,101,119,95,115,111,99,107,0,110,115,0,108,105,109,105,116,0,115,116,97,99,107,95,105, -110,100,101,120,0,105,110,116,101,114,110,0,115,116,97,99,107,95,105,110,100,101,120,95,101,120,116,0,108,111,99,120, -0,108,111,99,121,0,111,119,110,95,105,110,100,101,120,0,116,111,95,105,110,100,101,120,0,42,116,111,115,111,99,107, -0,42,108,105,110,107,0,42,110,101,119,95,110,111,100,101,0,117,115,101,114,110,97,109,101,91,51,50,93,0,108,97, -115,116,121,0,111,117,116,112,117,116,115,0,42,115,116,111,114,97,103,101,0,109,105,110,105,119,105,100,116,104,0,99, -117,115,116,111,109,49,0,99,117,115,116,111,109,50,0,99,117,115,116,111,109,51,0,99,117,115,116,111,109,52,0,110, -101,101,100,95,101,120,101,99,0,101,120,101,99,0,116,111,116,114,0,98,117,116,114,0,112,114,118,114,0,42,116,121, -112,101,105,110,102,111,0,42,102,114,111,109,110,111,100,101,0,42,116,111,110,111,100,101,0,42,102,114,111,109,115,111, -99,107,0,110,111,100,101,115,0,108,105,110,107,115,0,42,115,116,97,99,107,0,42,116,104,114,101,97,100,115,116,97, -99,107,0,105,110,105,116,0,115,116,97,99,107,115,105,122,101,0,99,117,114,95,105,110,100,101,120,0,97,108,108,116, -121,112,101,115,0,42,111,119,110,116,121,112,101,0,42,115,101,108,105,110,0,42,115,101,108,111,117,116,0,40,42,116, -105,109,101,99,117,114,115,111,114,41,40,41,0,40,42,115,116,97,116,115,95,100,114,97,119,41,40,41,0,40,42,116, -101,115,116,95,98,114,101,97,107,41,40,41,0,99,121,99,108,105,99,0,109,111,118,105,101,0,115,97,109,112,108,101, -115,0,109,105,110,115,112,101,101,100,0,112,101,114,99,101,110,116,120,0,112,101,114,99,101,110,116,121,0,98,111,107, -101,104,0,99,117,114,118,101,100,0,105,109,97,103,101,95,105,110,95,119,105,100,116,104,0,105,109,97,103,101,95,105, -110,95,104,101,105,103,104,116,0,99,101,110,116,101,114,95,120,0,99,101,110,116,101,114,95,121,0,115,112,105,110,0, -105,116,101,114,0,119,114,97,112,0,115,105,103,109,97,95,99,111,108,111,114,0,115,105,103,109,97,95,115,112,97,99, -101,0,104,117,101,0,115,97,116,0,116,49,0,116,50,0,116,51,0,102,115,116,114,101,110,103,116,104,0,102,97,108, -112,104,97,0,107,101,121,91,52,93,0,120,49,0,120,50,0,121,49,0,121,50,0,99,111,108,110,97,109,101,91,51, -50,93,0,98,107,116,121,112,101,0,114,111,116,97,116,105,111,110,0,112,114,101,118,105,101,119,0,103,97,109,99,111, -0,110,111,95,122,98,117,102,0,102,115,116,111,112,0,109,97,120,98,108,117,114,0,98,116,104,114,101,115,104,0,42, -100,105,99,116,0,42,110,111,100,101,0,97,110,103,108,101,95,111,102,115,0,99,111,108,109,111,100,0,109,105,120,0, -116,104,114,101,115,104,111,108,100,0,102,97,100,101,0,109,0,99,0,106,105,116,0,112,114,111,106,0,102,105,116,0, -115,104,111,114,116,121,0,109,105,110,116,97,98,108,101,0,109,97,120,116,97,98,108,101,0,101,120,116,95,105,110,91, -50,93,0,101,120,116,95,111,117,116,91,50,93,0,42,99,117,114,118,101,0,42,116,97,98,108,101,0,42,112,114,101, -109,117,108,116,97,98,108,101,0,99,117,114,114,0,99,108,105,112,114,0,99,109,91,52,93,0,98,108,97,99,107,91, -51,93,0,119,104,105,116,101,91,51,93,0,98,119,109,117,108,91,51,93,0,115,97,109,112,108,101,91,51,93,0,111, -102,102,115,101,116,91,50,93,0,105,110,110,101,114,114,97,100,105,117,115,0,114,97,116,101,0,114,103,98,91,51,93, -0,99,108,111,110,101,0,97,99,116,105,118,101,95,114,110,100,0,97,99,116,105,118,101,95,99,108,111,110,101,0,97, -99,116,105,118,101,95,109,97,115,107,0,42,108,97,121,101,114,115,0,116,111,116,108,97,121,101,114,0,109,97,120,108, -97,121,101,114,0,116,111,116,115,105,122,101,0,42,112,111,111,108,0,101,100,105,116,102,108,97,103,0,118,101,108,91, -51,93,0,114,111,116,91,52,93,0,97,118,101,91,51,93,0,110,117,109,0,112,97,114,101,110,116,0,112,97,91,52, -93,0,119,91,52,93,0,102,117,118,91,52,93,0,102,111,102,102,115,101,116,0,114,97,110,100,91,51,93,0,42,115, -116,105,99,107,95,111,98,0,112,114,101,118,95,115,116,97,116,101,0,42,104,97,105,114,0,105,95,114,111,116,91,52, -93,0,114,95,114,111,116,91,52,93,0,114,95,97,118,101,91,51,93,0,114,95,118,101,91,51,93,0,100,105,101,116, -105,109,101,0,98,97,110,107,0,115,105,122,101,109,117,108,0,110,117,109,95,100,109,99,97,99,104,101,0,98,112,105, -0,97,108,105,118,101,0,108,111,111,112,0,100,105,115,116,114,0,112,104,121,115,116,121,112,101,0,114,111,116,109,111, -100,101,0,97,118,101,109,111,100,101,0,114,101,97,99,116,101,118,101,110,116,0,100,114,97,119,0,100,114,97,119,95, -97,115,0,100,114,97,119,95,115,105,122,101,0,99,104,105,108,100,116,121,112,101,0,100,114,97,119,95,115,116,101,112, -0,114,101,110,95,115,116,101,112,0,104,97,105,114,95,115,116,101,112,0,107,101,121,115,95,115,116,101,112,0,97,100, -97,112,116,95,97,110,103,108,101,0,97,100,97,112,116,95,112,105,120,0,114,111,116,102,114,111,109,0,105,110,116,101, -103,114,97,116,111,114,0,110,98,101,116,119,101,101,110,0,98,111,105,100,110,101,105,103,104,98,111,117,114,115,0,98, -98,95,97,108,105,103,110,0,98,98,95,117,118,95,115,112,108,105,116,0,98,98,95,97,110,105,109,0,98,98,95,115, -112,108,105,116,95,111,102,102,115,101,116,0,98,98,95,116,105,108,116,0,98,98,95,114,97,110,100,95,116,105,108,116, -0,98,98,95,111,102,102,115,101,116,91,50,93,0,115,105,109,112,108,105,102,121,95,102,108,97,103,0,115,105,109,112, -108,105,102,121,95,114,101,102,115,105,122,101,0,115,105,109,112,108,105,102,121,95,114,97,116,101,0,115,105,109,112,108, -105,102,121,95,116,114,97,110,115,105,116,105,111,110,0,115,105,109,112,108,105,102,121,95,118,105,101,119,112,111,114,116, -0,116,105,109,101,116,119,101,97,107,0,106,105,116,102,97,99,0,107,101,121,101,100,95,116,105,109,101,0,101,102,102, -95,104,97,105,114,0,103,114,105,100,95,114,101,115,0,112,97,114,116,102,97,99,0,116,97,110,102,97,99,0,116,97, -110,112,104,97,115,101,0,114,101,97,99,116,102,97,99,0,97,118,101,102,97,99,0,112,104,97,115,101,102,97,99,0, -114,97,110,100,114,111,116,102,97,99,0,114,97,110,100,112,104,97,115,101,102,97,99,0,114,97,110,100,115,105,122,101, -0,114,101,97,99,116,115,104,97,112,101,0,97,99,99,91,51,93,0,100,114,97,103,102,97,99,0,98,114,111,119,110, -102,97,99,0,100,97,109,112,102,97,99,0,97,98,115,108,101,110,103,116,104,0,114,97,110,100,108,101,110,103,116,104, -0,99,104,105,108,100,95,110,98,114,0,114,101,110,95,99,104,105,108,100,95,110,98,114,0,112,97,114,101,110,116,115, -0,99,104,105,108,100,115,105,122,101,0,99,104,105,108,100,114,97,110,100,115,105,122,101,0,99,104,105,108,100,114,97, -100,0,99,104,105,108,100,102,108,97,116,0,99,104,105,108,100,115,112,114,101,97,100,0,99,108,117,109,112,102,97,99, -0,99,108,117,109,112,112,111,119,0,114,111,117,103,104,49,0,114,111,117,103,104,49,95,115,105,122,101,0,114,111,117, -103,104,50,0,114,111,117,103,104,50,95,115,105,122,101,0,114,111,117,103,104,50,95,116,104,114,101,115,0,114,111,117, -103,104,95,101,110,100,0,114,111,117,103,104,95,101,110,100,95,115,104,97,112,101,0,98,114,97,110,99,104,95,116,104, -114,101,115,0,100,114,97,119,95,108,105,110,101,91,50,93,0,109,97,120,95,108,97,116,95,97,99,99,0,109,97,120, -95,116,97,110,95,97,99,99,0,97,118,101,114,97,103,101,95,118,101,108,0,98,97,110,107,105,110,103,0,109,97,120, -95,98,97,110,107,0,103,114,111,117,110,100,122,0,98,111,105,100,102,97,99,91,56,93,0,98,111,105,100,114,117,108, -101,91,56,93,0,42,101,102,102,95,103,114,111,117,112,0,42,100,117,112,95,111,98,0,42,98,98,95,111,98,0,42, -112,100,50,0,42,112,97,114,116,0,42,101,100,105,116,0,42,42,112,97,116,104,99,97,99,104,101,0,42,42,99,104, -105,108,100,99,97,99,104,101,0,112,97,116,104,99,97,99,104,101,98,117,102,115,0,99,104,105,108,100,99,97,99,104, -101,98,117,102,115,0,42,116,97,114,103,101,116,95,111,98,0,42,107,101,121,101,100,95,111,98,0,42,108,97,116,116, -105,99,101,0,101,102,102,101,99,116,111,114,115,0,114,101,97,99,116,101,118,101,110,116,115,0,116,111,116,99,104,105, -108,100,0,116,111,116,99,97,99,104,101,100,0,116,111,116,99,104,105,108,100,99,97,99,104,101,0,116,97,114,103,101, -116,95,112,115,121,115,0,107,101,121,101,100,95,112,115,121,115,0,116,111,116,107,101,121,101,100,0,98,97,107,101,115, -112,97,99,101,0,98,98,95,117,118,110,97,109,101,91,51,93,91,51,50,93,0,118,103,114,111,117,112,91,49,50,93, -0,118,103,95,110,101,103,0,114,116,51,0,42,114,101,110,100,101,114,100,97,116,97,0,42,99,97,99,104,101,0,67, -100,105,115,0,67,118,105,0,91,51,93,0,115,116,114,117,99,116,117,114,97,108,0,98,101,110,100,105,110,103,0,109, -97,120,95,98,101,110,100,0,109,97,120,95,115,116,114,117,99,116,0,109,97,120,95,115,104,101,97,114,0,97,118,103, -95,115,112,114,105,110,103,95,108,101,110,0,116,105,109,101,115,99,97,108,101,0,101,102,102,95,102,111,114,99,101,95, -115,99,97,108,101,0,101,102,102,95,119,105,110,100,95,115,99,97,108,101,0,115,105,109,95,116,105,109,101,95,111,108, -100,0,115,116,101,112,115,80,101,114,70,114,97,109,101,0,112,114,101,114,111,108,108,0,109,97,120,115,112,114,105,110, -103,108,101,110,0,115,111,108,118,101,114,95,116,121,112,101,0,118,103,114,111,117,112,95,98,101,110,100,0,118,103,114, -111,117,112,95,109,97,115,115,0,118,103,114,111,117,112,95,115,116,114,117,99,116,0,112,114,101,115,101,116,115,0,42, -99,111,108,108,105,115,105,111,110,95,108,105,115,116,0,101,112,115,105,108,111,110,0,115,101,108,102,95,102,114,105,99, -116,105,111,110,0,115,101,108,102,101,112,115,105,108,111,110,0,115,101,108,102,95,108,111,111,112,95,99,111,117,110,116, -0,108,111,111,112,95,99,111,117,110,116,0,112,114,101,115,115,117,114,101,0,42,112,111,105,110,116,115,0,116,111,116, -112,111,105,110,116,115,0,116,104,105,99,107,110,101,115,115,0,115,116,114,111,107,101,115,0,102,114,97,109,101,110,117, -109,0,42,97,99,116,102,114,97,109,101,0,103,115,116,101,112,0,105,110,102,111,91,49,50,56,93,0,115,98,117,102, -102,101,114,95,115,105,122,101,0,115,98,117,102,102,101,114,95,115,102,108,97,103,0,42,115,98,117,102,102,101,114,0, -0,0,0,84,89,80,69,100,1,0,0,99,104,97,114,0,117,99,104,97,114,0,115,104,111,114,116,0,117,115,104,111, -114,116,0,105,110,116,0,108,111,110,103,0,117,108,111,110,103,0,102,108,111,97,116,0,100,111,117,98,108,101,0,118, -111,105,100,0,76,105,110,107,0,76,105,110,107,68,97,116,97,0,76,105,115,116,66,97,115,101,0,118,101,99,50,115, -0,118,101,99,50,105,0,118,101,99,50,102,0,118,101,99,50,100,0,118,101,99,51,105,0,118,101,99,51,102,0,118, -101,99,51,100,0,118,101,99,52,105,0,118,101,99,52,102,0,118,101,99,52,100,0,114,99,116,105,0,114,99,116,102, -0,73,68,80,114,111,112,101,114,116,121,68,97,116,97,0,73,68,80,114,111,112,101,114,116,121,0,73,68,0,76,105, -98,114,97,114,121,0,70,105,108,101,68,97,116,97,0,80,114,101,118,105,101,119,73,109,97,103,101,0,73,112,111,68, -114,105,118,101,114,0,79,98,106,101,99,116,0,73,112,111,67,117,114,118,101,0,66,80,111,105,110,116,0,66,101,122, -84,114,105,112,108,101,0,73,112,111,0,75,101,121,66,108,111,99,107,0,75,101,121,0,83,99,114,105,112,116,76,105, -110,107,0,84,101,120,116,76,105,110,101,0,84,101,120,116,77,97,114,107,101,114,0,84,101,120,116,0,80,97,99,107, -101,100,70,105,108,101,0,67,97,109,101,114,97,0,73,109,97,103,101,85,115,101,114,0,73,109,97,103,101,0,71,80, -85,84,101,120,116,117,114,101,0,97,110,105,109,0,82,101,110,100,101,114,82,101,115,117,108,116,0,77,84,101,120,0, -84,101,120,0,80,108,117,103,105,110,84,101,120,0,67,66,68,97,116,97,0,67,111,108,111,114,66,97,110,100,0,69, -110,118,77,97,112,0,73,109,66,117,102,0,98,78,111,100,101,84,114,101,101,0,84,101,120,77,97,112,112,105,110,103, -0,76,97,109,112,0,67,117,114,118,101,77,97,112,112,105,110,103,0,87,97,118,101,0,77,97,116,101,114,105,97,108, -0,71,114,111,117,112,0,86,70,111,110,116,0,86,70,111,110,116,68,97,116,97,0,77,101,116,97,69,108,101,109,0, -66,111,117,110,100,66,111,120,0,77,101,116,97,66,97,108,108,0,78,117,114,98,0,67,104,97,114,73,110,102,111,0, -84,101,120,116,66,111,120,0,67,117,114,118,101,0,80,97,116,104,0,77,101,115,104,0,77,70,97,99,101,0,77,84, -70,97,99,101,0,84,70,97,99,101,0,77,86,101,114,116,0,77,69,100,103,101,0,77,68,101,102,111,114,109,86,101, -114,116,0,77,67,111,108,0,77,83,116,105,99,107,121,0,77,83,101,108,101,99,116,0,67,117,115,116,111,109,68,97, -116,97,0,77,117,108,116,105,114,101,115,0,80,97,114,116,105,97,108,86,105,115,105,98,105,108,105,116,121,0,77,68, -101,102,111,114,109,87,101,105,103,104,116,0,77,84,101,120,80,111,108,121,0,77,76,111,111,112,85,86,0,77,76,111, -111,112,67,111,108,0,77,70,108,111,97,116,80,114,111,112,101,114,116,121,0,77,73,110,116,80,114,111,112,101,114,116, -121,0,77,83,116,114,105,110,103,80,114,111,112,101,114,116,121,0,79,114,105,103,83,112,97,99,101,70,97,99,101,0, -77,117,108,116,105,114,101,115,67,111,108,0,77,117,108,116,105,114,101,115,67,111,108,70,97,99,101,0,77,117,108,116, -105,114,101,115,70,97,99,101,0,77,117,108,116,105,114,101,115,69,100,103,101,0,77,117,108,116,105,114,101,115,76,101, -118,101,108,0,77,117,108,116,105,114,101,115,77,97,112,78,111,100,101,0,77,111,100,105,102,105,101,114,68,97,116,97, -0,83,117,98,115,117,114,102,77,111,100,105,102,105,101,114,68,97,116,97,0,76,97,116,116,105,99,101,77,111,100,105, -102,105,101,114,68,97,116,97,0,67,117,114,118,101,77,111,100,105,102,105,101,114,68,97,116,97,0,66,117,105,108,100, -77,111,100,105,102,105,101,114,68,97,116,97,0,77,97,115,107,77,111,100,105,102,105,101,114,68,97,116,97,0,65,114, -114,97,121,77,111,100,105,102,105,101,114,68,97,116,97,0,77,105,114,114,111,114,77,111,100,105,102,105,101,114,68,97, -116,97,0,69,100,103,101,83,112,108,105,116,77,111,100,105,102,105,101,114,68,97,116,97,0,66,101,118,101,108,77,111, -100,105,102,105,101,114,68,97,116,97,0,66,77,101,115,104,77,111,100,105,102,105,101,114,68,97,116,97,0,68,105,115, -112,108,97,99,101,77,111,100,105,102,105,101,114,68,97,116,97,0,85,86,80,114,111,106,101,99,116,77,111,100,105,102, -105,101,114,68,97,116,97,0,68,101,99,105,109,97,116,101,77,111,100,105,102,105,101,114,68,97,116,97,0,83,109,111, -111,116,104,77,111,100,105,102,105,101,114,68,97,116,97,0,67,97,115,116,77,111,100,105,102,105,101,114,68,97,116,97, -0,87,97,118,101,77,111,100,105,102,105,101,114,68,97,116,97,0,65,114,109,97,116,117,114,101,77,111,100,105,102,105, -101,114,68,97,116,97,0,72,111,111,107,77,111,100,105,102,105,101,114,68,97,116,97,0,83,111,102,116,98,111,100,121, -77,111,100,105,102,105,101,114,68,97,116,97,0,67,108,111,116,104,77,111,100,105,102,105,101,114,68,97,116,97,0,67, -108,111,116,104,0,67,108,111,116,104,83,105,109,83,101,116,116,105,110,103,115,0,67,108,111,116,104,67,111,108,108,83, -101,116,116,105,110,103,115,0,80,111,105,110,116,67,97,99,104,101,0,67,111,108,108,105,115,105,111,110,77,111,100,105, -102,105,101,114,68,97,116,97,0,66,86,72,84,114,101,101,0,83,117,114,102,97,99,101,77,111,100,105,102,105,101,114, -68,97,116,97,0,68,101,114,105,118,101,100,77,101,115,104,0,66,86,72,84,114,101,101,70,114,111,109,77,101,115,104, -0,66,111,111,108,101,97,110,77,111,100,105,102,105,101,114,68,97,116,97,0,77,68,101,102,73,110,102,108,117,101,110, -99,101,0,77,68,101,102,67,101,108,108,0,77,101,115,104,68,101,102,111,114,109,77,111,100,105,102,105,101,114,68,97, -116,97,0,80,97,114,116,105,99,108,101,83,121,115,116,101,109,77,111,100,105,102,105,101,114,68,97,116,97,0,80,97, -114,116,105,99,108,101,83,121,115,116,101,109,0,80,97,114,116,105,99,108,101,73,110,115,116,97,110,99,101,77,111,100, -105,102,105,101,114,68,97,116,97,0,69,120,112,108,111,100,101,77,111,100,105,102,105,101,114,68,97,116,97,0,70,108, -117,105,100,115,105,109,77,111,100,105,102,105,101,114,68,97,116,97,0,70,108,117,105,100,115,105,109,83,101,116,116,105, -110,103,115,0,83,104,114,105,110,107,119,114,97,112,77,111,100,105,102,105,101,114,68,97,116,97,0,83,105,109,112,108, -101,68,101,102,111,114,109,77,111,100,105,102,105,101,114,68,97,116,97,0,76,97,116,116,105,99,101,0,98,68,101,102, -111,114,109,71,114,111,117,112,0,98,65,99,116,105,111,110,0,98,80,111,115,101,0,66,117,108,108,101,116,83,111,102, -116,66,111,100,121,0,80,97,114,116,68,101,102,108,101,99,116,0,83,111,102,116,66,111,100,121,0,79,98,72,111,111, -107,0,82,78,71,0,83,66,86,101,114,116,101,120,0,66,111,100,121,80,111,105,110,116,0,66,111,100,121,83,112,114, -105,110,103,0,83,66,83,99,114,97,116,99,104,0,87,111,114,108,100,0,82,97,100,105,111,0,66,97,115,101,0,65, -118,105,67,111,100,101,99,68,97,116,97,0,81,117,105,99,107,116,105,109,101,67,111,100,101,99,68,97,116,97,0,70, -70,77,112,101,103,67,111,100,101,99,68,97,116,97,0,65,117,100,105,111,68,97,116,97,0,83,99,101,110,101,82,101, -110,100,101,114,76,97,121,101,114,0,82,101,110,100,101,114,68,97,116,97,0,82,101,110,100,101,114,80,114,111,102,105, -108,101,0,71,97,109,101,70,114,97,109,105,110,103,0,84,105,109,101,77,97,114,107,101,114,0,73,109,97,103,101,80, -97,105,110,116,83,101,116,116,105,110,103,115,0,66,114,117,115,104,0,80,97,114,116,105,99,108,101,66,114,117,115,104, -68,97,116,97,0,80,97,114,116,105,99,108,101,69,100,105,116,83,101,116,116,105,110,103,115,0,84,114,97,110,115,102, -111,114,109,79,114,105,101,110,116,97,116,105,111,110,0,84,111,111,108,83,101,116,116,105,110,103,115,0,66,114,117,115, -104,68,97,116,97,0,83,99,117,108,112,116,68,97,116,97,0,83,99,117,108,112,116,83,101,115,115,105,111,110,0,83, -99,101,110,101,0,68,97,103,70,111,114,101,115,116,0,66,71,112,105,99,0,86,105,101,119,51,68,0,83,112,97,99, -101,76,105,110,107,0,83,99,114,65,114,101,97,0,82,101,110,100,101,114,73,110,102,111,0,82,101,116,111,112,111,86, -105,101,119,68,97,116,97,0,86,105,101,119,68,101,112,116,104,115,0,98,71,80,100,97,116,97,0,86,105,101,119,50, -68,0,83,112,97,99,101,73,110,102,111,0,83,112,97,99,101,73,112,111,0,83,112,97,99,101,66,117,116,115,0,83, -112,97,99,101,83,101,113,0,83,112,97,99,101,70,105,108,101,0,100,105,114,101,110,116,114,121,0,66,108,101,110,100, -72,97,110,100,108,101,0,83,112,97,99,101,79,111,112,115,0,84,114,101,101,83,116,111,114,101,0,84,114,101,101,83, -116,111,114,101,69,108,101,109,0,83,112,97,99,101,73,109,97,103,101,0,83,112,97,99,101,78,108,97,0,83,112,97, -99,101,84,101,120,116,0,83,99,114,105,112,116,0,83,112,97,99,101,83,99,114,105,112,116,0,83,112,97,99,101,84, -105,109,101,0,83,112,97,99,101,78,111,100,101,0,83,112,97,99,101,73,109,97,83,101,108,0,70,105,108,101,76,105, -115,116,0,84,104,101,109,101,85,73,0,84,104,101,109,101,83,112,97,99,101,0,84,104,101,109,101,87,105,114,101,67, -111,108,111,114,0,98,84,104,101,109,101,0,83,111,108,105,100,76,105,103,104,116,0,85,115,101,114,68,101,102,0,98, -83,99,114,101,101,110,0,83,99,114,86,101,114,116,0,83,99,114,69,100,103,101,0,80,97,110,101,108,0,70,105,108, -101,71,108,111,98,97,108,0,83,116,114,105,112,69,108,101,109,0,84,83,116,114,105,112,69,108,101,109,0,83,116,114, -105,112,67,114,111,112,0,83,116,114,105,112,84,114,97,110,115,102,111,114,109,0,83,116,114,105,112,67,111,108,111,114, -66,97,108,97,110,99,101,0,83,116,114,105,112,67,111,108,111,114,66,97,108,97,110,99,101,71,85,73,72,101,108,112, -101,114,0,83,116,114,105,112,80,114,111,120,121,0,83,116,114,105,112,0,80,108,117,103,105,110,83,101,113,0,83,101, -113,117,101,110,99,101,0,98,83,111,117,110,100,0,104,100,97,117,100,105,111,0,77,101,116,97,83,116,97,99,107,0, -69,100,105,116,105,110,103,0,87,105,112,101,86,97,114,115,0,71,108,111,119,86,97,114,115,0,84,114,97,110,115,102, -111,114,109,86,97,114,115,0,83,111,108,105,100,67,111,108,111,114,86,97,114,115,0,83,112,101,101,100,67,111,110,116, -114,111,108,86,97,114,115,0,69,102,102,101,99,116,0,66,117,105,108,100,69,102,102,0,80,97,114,116,69,102,102,0, -80,97,114,116,105,99,108,101,0,87,97,118,101,69,102,102,0,79,111,112,115,0,98,80,114,111,112,101,114,116,121,0, -98,78,101,97,114,83,101,110,115,111,114,0,98,77,111,117,115,101,83,101,110,115,111,114,0,98,84,111,117,99,104,83, -101,110,115,111,114,0,98,75,101,121,98,111,97,114,100,83,101,110,115,111,114,0,98,80,114,111,112,101,114,116,121,83, -101,110,115,111,114,0,98,65,99,116,117,97,116,111,114,83,101,110,115,111,114,0,98,68,101,108,97,121,83,101,110,115, -111,114,0,98,67,111,108,108,105,115,105,111,110,83,101,110,115,111,114,0,98,82,97,100,97,114,83,101,110,115,111,114, -0,98,82,97,110,100,111,109,83,101,110,115,111,114,0,98,82,97,121,83,101,110,115,111,114,0,98,77,101,115,115,97, -103,101,83,101,110,115,111,114,0,98,83,101,110,115,111,114,0,98,67,111,110,116,114,111,108,108,101,114,0,98,74,111, -121,115,116,105,99,107,83,101,110,115,111,114,0,98,69,120,112,114,101,115,115,105,111,110,67,111,110,116,0,98,80,121, -116,104,111,110,67,111,110,116,0,98,65,99,116,117,97,116,111,114,0,98,65,100,100,79,98,106,101,99,116,65,99,116, -117,97,116,111,114,0,98,65,99,116,105,111,110,65,99,116,117,97,116,111,114,0,98,83,111,117,110,100,65,99,116,117, -97,116,111,114,0,98,67,68,65,99,116,117,97,116,111,114,0,98,69,100,105,116,79,98,106,101,99,116,65,99,116,117, -97,116,111,114,0,98,83,99,101,110,101,65,99,116,117,97,116,111,114,0,98,80,114,111,112,101,114,116,121,65,99,116, -117,97,116,111,114,0,98,79,98,106,101,99,116,65,99,116,117,97,116,111,114,0,98,73,112,111,65,99,116,117,97,116, -111,114,0,98,67,97,109,101,114,97,65,99,116,117,97,116,111,114,0,98,67,111,110,115,116,114,97,105,110,116,65,99, -116,117,97,116,111,114,0,98,71,114,111,117,112,65,99,116,117,97,116,111,114,0,98,82,97,110,100,111,109,65,99,116, -117,97,116,111,114,0,98,77,101,115,115,97,103,101,65,99,116,117,97,116,111,114,0,98,71,97,109,101,65,99,116,117, -97,116,111,114,0,98,86,105,115,105,98,105,108,105,116,121,65,99,116,117,97,116,111,114,0,98,84,119,111,68,70,105, -108,116,101,114,65,99,116,117,97,116,111,114,0,98,80,97,114,101,110,116,65,99,116,117,97,116,111,114,0,98,83,116, -97,116,101,65,99,116,117,97,116,111,114,0,70,114,101,101,67,97,109,101,114,97,0,98,83,97,109,112,108,101,0,98, -83,111,117,110,100,76,105,115,116,101,110,101,114,0,83,112,97,99,101,83,111,117,110,100,0,71,114,111,117,112,79,98, -106,101,99,116,0,66,111,110,101,0,98,65,114,109,97,116,117,114,101,0,98,80,111,115,101,67,104,97,110,110,101,108, -0,98,65,99,116,105,111,110,71,114,111,117,112,0,98,65,99,116,105,111,110,67,104,97,110,110,101,108,0,83,112,97, -99,101,65,99,116,105,111,110,0,98,67,111,110,115,116,114,97,105,110,116,67,104,97,110,110,101,108,0,98,67,111,110, -115,116,114,97,105,110,116,0,98,67,111,110,115,116,114,97,105,110,116,84,97,114,103,101,116,0,98,80,121,116,104,111, -110,67,111,110,115,116,114,97,105,110,116,0,98,75,105,110,101,109,97,116,105,99,67,111,110,115,116,114,97,105,110,116, -0,98,84,114,97,99,107,84,111,67,111,110,115,116,114,97,105,110,116,0,98,82,111,116,97,116,101,76,105,107,101,67, -111,110,115,116,114,97,105,110,116,0,98,76,111,99,97,116,101,76,105,107,101,67,111,110,115,116,114,97,105,110,116,0, -98,77,105,110,77,97,120,67,111,110,115,116,114,97,105,110,116,0,98,83,105,122,101,76,105,107,101,67,111,110,115,116, -114,97,105,110,116,0,98,65,99,116,105,111,110,67,111,110,115,116,114,97,105,110,116,0,98,76,111,99,107,84,114,97, -99,107,67,111,110,115,116,114,97,105,110,116,0,98,70,111,108,108,111,119,80,97,116,104,67,111,110,115,116,114,97,105, -110,116,0,98,83,116,114,101,116,99,104,84,111,67,111,110,115,116,114,97,105,110,116,0,98,82,105,103,105,100,66,111, -100,121,74,111,105,110,116,67,111,110,115,116,114,97,105,110,116,0,98,67,108,97,109,112,84,111,67,111,110,115,116,114, -97,105,110,116,0,98,67,104,105,108,100,79,102,67,111,110,115,116,114,97,105,110,116,0,98,84,114,97,110,115,102,111, -114,109,67,111,110,115,116,114,97,105,110,116,0,98,76,111,99,76,105,109,105,116,67,111,110,115,116,114,97,105,110,116, -0,98,82,111,116,76,105,109,105,116,67,111,110,115,116,114,97,105,110,116,0,98,83,105,122,101,76,105,109,105,116,67, -111,110,115,116,114,97,105,110,116,0,98,68,105,115,116,76,105,109,105,116,67,111,110,115,116,114,97,105,110,116,0,98, -83,104,114,105,110,107,119,114,97,112,67,111,110,115,116,114,97,105,110,116,0,98,65,99,116,105,111,110,77,111,100,105, -102,105,101,114,0,98,65,99,116,105,111,110,83,116,114,105,112,0,98,78,111,100,101,83,116,97,99,107,0,98,78,111, -100,101,83,111,99,107,101,116,0,98,78,111,100,101,76,105,110,107,0,98,78,111,100,101,0,98,78,111,100,101,80,114, -101,118,105,101,119,0,98,78,111,100,101,84,121,112,101,0,78,111,100,101,73,109,97,103,101,65,110,105,109,0,78,111, -100,101,66,108,117,114,68,97,116,97,0,78,111,100,101,68,66,108,117,114,68,97,116,97,0,78,111,100,101,66,105,108, -97,116,101,114,97,108,66,108,117,114,68,97,116,97,0,78,111,100,101,72,117,101,83,97,116,0,78,111,100,101,73,109, -97,103,101,70,105,108,101,0,78,111,100,101,67,104,114,111,109,97,0,78,111,100,101,84,119,111,88,89,115,0,78,111, -100,101,84,119,111,70,108,111,97,116,115,0,78,111,100,101,71,101,111,109,101,116,114,121,0,78,111,100,101,86,101,114, -116,101,120,67,111,108,0,78,111,100,101,68,101,102,111,99,117,115,0,78,111,100,101,83,99,114,105,112,116,68,105,99, -116,0,78,111,100,101,71,108,97,114,101,0,78,111,100,101,84,111,110,101,109,97,112,0,78,111,100,101,76,101,110,115, -68,105,115,116,0,84,101,120,78,111,100,101,79,117,116,112,117,116,0,67,117,114,118,101,77,97,112,80,111,105,110,116, -0,67,117,114,118,101,77,97,112,0,66,114,117,115,104,67,108,111,110,101,0,67,117,115,116,111,109,68,97,116,97,76, -97,121,101,114,0,72,97,105,114,75,101,121,0,80,97,114,116,105,99,108,101,75,101,121,0,67,104,105,108,100,80,97, -114,116,105,99,108,101,0,80,97,114,116,105,99,108,101,68,97,116,97,0,80,97,114,116,105,99,108,101,83,101,116,116, -105,110,103,115,0,80,97,114,116,105,99,108,101,69,100,105,116,0,80,97,114,116,105,99,108,101,67,97,99,104,101,75, -101,121,0,76,105,110,107,78,111,100,101,0,98,71,80,68,115,112,111,105,110,116,0,98,71,80,68,115,116,114,111,107, -101,0,98,71,80,68,102,114,97,109,101,0,98,71,80,68,108,97,121,101,114,0,0,84,76,69,78,1,0,1,0,2, -0,2,0,4,0,4,0,4,0,4,0,8,0,0,0,16,0,24,0,16,0,4,0,8,0,8,0,16,0,12,0,12, -0,24,0,16,0,16,0,32,0,16,0,16,0,32,0,96,0,72,0,72,2,0,0,40,0,-112,0,48,4,112,0,36, -0,56,0,112,0,-128,0,-96,0,24,0,40,0,48,0,-80,0,24,0,-88,0,32,0,-72,1,0,0,0,0,0,0,-112, -0,64,1,120,1,24,0,8,3,-56,0,0,0,-56,0,-120,0,-16,1,56,1,80,0,-16,2,104,0,96,1,0,0,-128, -0,104,0,-72,0,80,0,8,0,16,0,-96,1,0,0,-112,1,20,0,48,0,64,0,24,0,12,0,16,0,4,0,8, -0,8,0,32,0,112,0,48,0,8,0,16,0,8,0,8,0,4,0,4,0,0,1,32,0,16,0,64,0,24,0,12, -0,96,0,0,0,64,0,88,0,104,0,112,0,80,0,112,0,-112,0,80,0,72,0,120,0,72,0,-88,0,-48,0,72, -0,104,0,120,0,-48,0,120,0,-56,0,64,0,96,0,0,0,-120,0,32,0,20,0,-112,0,0,0,80,0,0,0,0, -0,80,0,8,0,8,0,0,1,96,0,-104,1,80,0,80,0,80,0,-72,1,-128,0,120,0,-104,0,48,0,-128,0,72, -0,120,0,-120,0,16,1,-32,0,0,0,16,0,0,0,0,0,0,0,-32,1,40,0,40,0,-72,0,-104,0,56,0,16, -0,88,0,-24,3,64,0,16,0,88,0,16,0,24,1,8,0,72,0,88,0,-16,0,8,0,-8,0,0,0,64,6,0, -0,64,0,88,3,48,0,8,1,0,0,0,0,0,0,32,0,-120,0,48,0,120,1,-16,0,-40,0,-8,1,0,0,0, -0,48,1,16,0,16,0,32,1,-64,0,-112,0,120,2,56,0,-80,0,0,1,-72,2,0,0,-104,0,-48,0,16,0,64, -14,56,0,40,12,-88,0,32,0,40,0,-16,0,40,0,80,0,48,0,16,0,8,0,64,0,0,0,0,1,32,1,-56, -1,8,1,72,1,0,0,32,0,48,0,12,0,24,0,48,0,16,0,32,0,24,0,32,0,72,1,0,0,64,0,64, -0,80,0,48,0,8,0,48,0,72,0,104,0,40,0,8,0,72,0,44,0,40,0,108,0,72,0,96,0,104,0,60, -0,-128,0,80,0,80,0,16,0,96,0,32,0,20,0,88,0,24,0,80,0,112,0,84,0,32,0,96,0,64,0,56, -0,112,0,-116,0,4,0,24,0,16,0,8,0,40,0,0,0,88,0,-64,0,40,0,24,1,-104,0,-48,1,88,0,88, -0,-48,0,56,0,80,0,-128,0,80,0,112,0,56,0,48,0,48,0,72,0,48,0,72,0,48,0,24,0,56,0,104, -0,16,0,112,0,96,0,28,0,28,0,28,0,56,0,24,0,72,0,-88,0,40,0,-112,0,48,0,-8,0,0,0,0, -0,16,0,40,0,28,0,12,0,12,0,16,1,40,0,8,0,8,0,64,0,32,0,24,0,16,0,24,0,32,0,8, -0,32,0,12,0,56,0,24,0,72,0,24,0,56,0,72,0,8,1,16,2,0,0,0,0,0,0,16,0,32,0,40, -0,-64,0,83,84,82,67,57,1,0,0,10,0,2,0,10,0,0,0,10,0,1,0,11,0,3,0,11,0,0,0,11, -0,1,0,9,0,2,0,12,0,2,0,9,0,3,0,9,0,4,0,13,0,2,0,2,0,5,0,2,0,6,0,14, -0,2,0,4,0,5,0,4,0,6,0,15,0,2,0,7,0,5,0,7,0,6,0,16,0,2,0,8,0,5,0,8, -0,6,0,17,0,3,0,4,0,5,0,4,0,6,0,4,0,7,0,18,0,3,0,7,0,5,0,7,0,6,0,7, -0,7,0,19,0,3,0,8,0,5,0,8,0,6,0,8,0,7,0,20,0,4,0,4,0,5,0,4,0,6,0,4, -0,7,0,4,0,8,0,21,0,4,0,7,0,5,0,7,0,6,0,7,0,7,0,7,0,8,0,22,0,4,0,8, -0,5,0,8,0,6,0,8,0,7,0,8,0,8,0,23,0,4,0,4,0,9,0,4,0,10,0,4,0,11,0,4, -0,12,0,24,0,4,0,7,0,9,0,7,0,10,0,7,0,11,0,7,0,12,0,25,0,4,0,9,0,13,0,12, -0,14,0,4,0,15,0,4,0,16,0,26,0,10,0,26,0,0,0,26,0,1,0,0,0,17,0,0,0,18,0,0, -0,19,0,2,0,20,0,4,0,21,0,25,0,22,0,4,0,23,0,4,0,24,0,27,0,9,0,9,0,0,0,9, -0,1,0,27,0,25,0,28,0,26,0,0,0,27,0,2,0,28,0,2,0,20,0,4,0,29,0,26,0,30,0,28, -0,8,0,27,0,31,0,27,0,32,0,29,0,33,0,0,0,34,0,0,0,35,0,4,0,36,0,4,0,37,0,28, -0,38,0,30,0,6,0,4,0,39,0,4,0,40,0,2,0,41,0,2,0,42,0,2,0,43,0,4,0,44,0,31, -0,6,0,32,0,45,0,2,0,46,0,2,0,47,0,2,0,18,0,2,0,20,0,0,0,48,0,33,0,21,0,33, -0,0,0,33,0,1,0,34,0,49,0,35,0,50,0,24,0,51,0,24,0,52,0,2,0,46,0,2,0,47,0,2, -0,53,0,2,0,54,0,2,0,55,0,2,0,56,0,2,0,20,0,2,0,57,0,7,0,11,0,7,0,12,0,4, -0,58,0,7,0,59,0,7,0,60,0,7,0,61,0,31,0,62,0,36,0,7,0,27,0,31,0,12,0,63,0,24, -0,64,0,2,0,46,0,2,0,65,0,2,0,66,0,2,0,37,0,37,0,16,0,37,0,0,0,37,0,1,0,7, -0,67,0,7,0,61,0,2,0,18,0,2,0,47,0,2,0,68,0,2,0,20,0,4,0,69,0,4,0,70,0,9, -0,2,0,7,0,71,0,0,0,17,0,0,0,72,0,7,0,73,0,7,0,74,0,38,0,12,0,27,0,31,0,37, -0,75,0,0,0,76,0,4,0,77,0,7,0,61,0,12,0,78,0,36,0,79,0,27,0,80,0,2,0,18,0,2, -0,81,0,2,0,82,0,2,0,20,0,39,0,5,0,27,0,83,0,2,0,84,0,2,0,85,0,2,0,86,0,4, -0,37,0,40,0,6,0,40,0,0,0,40,0,1,0,0,0,87,0,0,0,88,0,4,0,23,0,4,0,89,0,41, -0,10,0,41,0,0,0,41,0,1,0,4,0,90,0,4,0,91,0,4,0,92,0,4,0,43,0,4,0,14,0,4, -0,93,0,0,0,94,0,0,0,95,0,42,0,15,0,27,0,31,0,0,0,96,0,4,0,93,0,4,0,97,0,12, -0,98,0,40,0,99,0,40,0,100,0,4,0,101,0,4,0,102,0,12,0,103,0,0,0,104,0,4,0,105,0,4, -0,106,0,9,0,107,0,8,0,108,0,43,0,5,0,4,0,109,0,4,0,110,0,4,0,93,0,4,0,37,0,9, -0,2,0,44,0,20,0,27,0,31,0,2,0,18,0,2,0,20,0,7,0,111,0,7,0,112,0,7,0,113,0,7, -0,114,0,7,0,115,0,7,0,116,0,7,0,117,0,7,0,118,0,7,0,119,0,7,0,120,0,7,0,121,0,2, -0,122,0,2,0,123,0,7,0,124,0,36,0,79,0,39,0,125,0,32,0,126,0,45,0,12,0,4,0,127,0,4, -0,-128,0,4,0,-127,0,4,0,-126,0,2,0,-125,0,2,0,-124,0,2,0,20,0,2,0,-123,0,2,0,-122,0,2, -0,-121,0,2,0,-120,0,2,0,-119,0,46,0,32,0,27,0,31,0,0,0,34,0,12,0,-118,0,47,0,-117,0,48, -0,-116,0,49,0,-115,0,2,0,-123,0,2,0,20,0,2,0,-114,0,2,0,18,0,2,0,37,0,2,0,43,0,4, -0,-113,0,2,0,-112,0,2,0,-111,0,2,0,-110,0,2,0,-109,0,2,0,-108,0,2,0,-107,0,4,0,-106,0,4, -0,-105,0,43,0,-104,0,30,0,-103,0,7,0,-102,0,4,0,-101,0,2,0,-100,0,2,0,-99,0,2,0,-98,0,2, -0,-97,0,7,0,-96,0,7,0,-95,0,9,0,-94,0,50,0,31,0,2,0,-93,0,2,0,-92,0,2,0,-91,0,2, -0,-90,0,32,0,-89,0,51,0,-88,0,0,0,-87,0,0,0,-86,0,0,0,-85,0,0,0,-84,0,0,0,-83,0,7, -0,-82,0,7,0,-81,0,2,0,-80,0,2,0,-79,0,2,0,-78,0,2,0,-77,0,2,0,-76,0,2,0,-75,0,2, -0,-74,0,7,0,-73,0,7,0,-72,0,7,0,-71,0,7,0,-70,0,7,0,-69,0,7,0,57,0,7,0,-68,0,7, -0,-67,0,7,0,-66,0,7,0,-65,0,7,0,-64,0,52,0,15,0,0,0,-63,0,9,0,-62,0,0,0,-61,0,0, -0,-60,0,4,0,-59,0,4,0,-58,0,9,0,-57,0,7,0,-56,0,7,0,-55,0,7,0,-54,0,4,0,-53,0,9, -0,-52,0,9,0,-51,0,4,0,-50,0,4,0,37,0,53,0,6,0,7,0,-73,0,7,0,-72,0,7,0,-71,0,7, -0,-49,0,7,0,67,0,4,0,64,0,54,0,5,0,2,0,20,0,2,0,36,0,2,0,64,0,2,0,-48,0,53, -0,-54,0,55,0,17,0,32,0,-89,0,46,0,-47,0,56,0,-46,0,7,0,-45,0,7,0,-44,0,2,0,18,0,2, -0,-43,0,7,0,113,0,7,0,114,0,7,0,-42,0,4,0,-41,0,2,0,-40,0,2,0,-39,0,4,0,-123,0,4, -0,-113,0,2,0,-38,0,2,0,-37,0,51,0,56,0,27,0,31,0,7,0,-36,0,7,0,-35,0,7,0,-34,0,7, -0,-33,0,7,0,-32,0,7,0,-31,0,7,0,-30,0,7,0,-29,0,7,0,-28,0,7,0,-27,0,7,0,-26,0,7, -0,-25,0,7,0,-24,0,7,0,-23,0,7,0,-22,0,7,0,-21,0,7,0,-20,0,7,0,-19,0,7,0,-18,0,7, -0,-17,0,2,0,-16,0,2,0,-15,0,2,0,-14,0,2,0,-13,0,2,0,-12,0,2,0,-11,0,2,0,-10,0,2, -0,20,0,2,0,18,0,2,0,-43,0,7,0,-9,0,7,0,-8,0,7,0,-7,0,7,0,-6,0,2,0,-5,0,2, -0,-4,0,2,0,-3,0,2,0,-125,0,4,0,23,0,4,0,-128,0,4,0,-127,0,4,0,-126,0,7,0,-2,0,7, -0,-1,0,7,0,-67,0,45,0,0,1,57,0,1,1,36,0,79,0,46,0,-47,0,52,0,2,1,54,0,3,1,55, -0,4,1,30,0,-103,0,0,0,5,1,0,0,6,1,58,0,8,0,7,0,7,1,7,0,8,1,7,0,-81,0,4, -0,20,0,7,0,9,1,7,0,10,1,7,0,11,1,32,0,45,0,59,0,80,0,27,0,31,0,2,0,18,0,2, -0,12,1,4,0,13,1,2,0,-79,0,2,0,14,1,7,0,-73,0,7,0,-72,0,7,0,-71,0,7,0,-70,0,7, -0,15,1,7,0,16,1,7,0,17,1,7,0,18,1,7,0,19,1,7,0,20,1,7,0,21,1,7,0,22,1,7, -0,23,1,7,0,24,1,7,0,25,1,60,0,26,1,2,0,27,1,2,0,70,0,7,0,113,0,7,0,114,0,7, -0,28,1,7,0,29,1,7,0,30,1,2,0,31,1,2,0,32,1,2,0,33,1,2,0,34,1,0,0,35,1,0, -0,36,1,2,0,37,1,2,0,38,1,2,0,39,1,2,0,40,1,2,0,41,1,7,0,42,1,7,0,43,1,7, -0,44,1,7,0,45,1,2,0,46,1,2,0,43,0,2,0,47,1,2,0,48,1,2,0,49,1,2,0,50,1,7, -0,51,1,7,0,52,1,7,0,53,1,7,0,54,1,7,0,55,1,7,0,56,1,7,0,57,1,7,0,58,1,7, -0,59,1,7,0,60,1,7,0,61,1,7,0,62,1,2,0,63,1,2,0,64,1,4,0,65,1,4,0,66,1,2, -0,67,1,2,0,68,1,2,0,69,1,2,0,70,1,7,0,71,1,7,0,72,1,7,0,73,1,7,0,74,1,2, -0,75,1,2,0,76,1,50,0,77,1,36,0,79,0,30,0,-103,0,39,0,125,0,61,0,2,0,27,0,31,0,36, -0,79,0,62,0,-127,0,27,0,31,0,2,0,-79,0,2,0,20,0,7,0,-73,0,7,0,-72,0,7,0,-71,0,7, -0,78,1,7,0,79,1,7,0,80,1,7,0,81,1,7,0,82,1,7,0,83,1,7,0,84,1,7,0,85,1,7, -0,86,1,7,0,87,1,7,0,88,1,7,0,89,1,7,0,90,1,7,0,91,1,7,0,92,1,7,0,93,1,7, -0,94,1,7,0,95,1,7,0,96,1,7,0,97,1,7,0,98,1,7,0,99,1,7,0,100,1,7,0,101,1,7, -0,102,1,7,0,103,1,7,0,104,1,2,0,105,1,2,0,106,1,2,0,107,1,0,0,108,1,0,0,109,1,7, -0,110,1,7,0,111,1,2,0,112,1,2,0,113,1,7,0,114,1,7,0,115,1,7,0,116,1,7,0,117,1,2, -0,118,1,2,0,119,1,4,0,13,1,4,0,120,1,2,0,121,1,2,0,122,1,2,0,123,1,2,0,124,1,7, -0,125,1,7,0,126,1,7,0,127,1,7,0,-128,1,7,0,-127,1,7,0,-126,1,7,0,-125,1,7,0,-124,1,7, -0,-123,1,7,0,-122,1,0,0,-121,1,7,0,-120,1,7,0,-119,1,7,0,-118,1,4,0,-117,1,0,0,-116,1,0, -0,47,1,0,0,-115,1,0,0,5,1,2,0,-114,1,2,0,-113,1,2,0,64,1,2,0,-112,1,2,0,-111,1,2, -0,-110,1,7,0,-109,1,7,0,-108,1,7,0,-107,1,7,0,-106,1,7,0,-105,1,2,0,-93,0,2,0,-92,0,54, -0,-104,1,54,0,-103,1,0,0,-102,1,0,0,-101,1,0,0,-100,1,0,0,-99,1,2,0,-98,1,2,0,12,1,7, -0,-97,1,7,0,-96,1,50,0,77,1,57,0,1,1,36,0,79,0,63,0,-95,1,30,0,-103,0,7,0,-94,1,7, -0,-93,1,7,0,-92,1,7,0,-91,1,7,0,-90,1,2,0,-89,1,2,0,70,0,7,0,-88,1,7,0,-87,1,7, -0,-86,1,7,0,-85,1,7,0,-84,1,7,0,-83,1,7,0,-82,1,7,0,-81,1,7,0,-80,1,2,0,-79,1,2, -0,-78,1,7,0,-77,1,7,0,-76,1,7,0,-75,1,7,0,-74,1,7,0,-73,1,4,0,-72,1,4,0,-71,1,4, -0,-70,1,39,0,125,0,12,0,-69,1,64,0,6,0,27,0,31,0,0,0,-68,1,7,0,-67,1,7,0,37,0,65, -0,2,0,43,0,-104,0,66,0,26,0,66,0,0,0,66,0,1,0,67,0,-66,1,4,0,-65,1,4,0,-64,1,4, -0,-63,1,4,0,-62,1,4,0,-61,1,4,0,-60,1,2,0,18,0,2,0,20,0,2,0,-59,1,2,0,-58,1,7, -0,5,0,7,0,6,0,7,0,7,0,7,0,-57,1,7,0,-56,1,7,0,-55,1,7,0,-54,1,7,0,-53,1,7, -0,-52,1,7,0,-51,1,7,0,23,0,7,0,-50,1,7,0,-49,1,68,0,15,0,27,0,31,0,67,0,-66,1,12, -0,-48,1,12,0,-47,1,36,0,79,0,62,0,-46,1,2,0,20,0,2,0,-45,1,4,0,-80,0,7,0,7,1,7, -0,-81,0,7,0,8,1,7,0,-44,1,7,0,-43,1,7,0,-42,1,35,0,10,0,7,0,-41,1,7,0,-40,1,7, -0,-39,1,7,0,-38,1,2,0,-37,1,2,0,-36,1,0,0,-35,1,0,0,-34,1,0,0,-33,1,0,0,-32,1,34, -0,7,0,7,0,-31,1,7,0,-40,1,7,0,-39,1,2,0,-35,1,2,0,-32,1,7,0,-38,1,7,0,37,0,69, -0,21,0,69,0,0,0,69,0,1,0,2,0,18,0,2,0,-30,1,2,0,-32,1,2,0,20,0,2,0,-29,1,2, -0,-28,1,2,0,-27,1,2,0,-26,1,2,0,-25,1,2,0,-24,1,2,0,-23,1,2,0,-22,1,7,0,-21,1,7, -0,-20,1,34,0,49,0,35,0,50,0,2,0,-19,1,2,0,-18,1,4,0,-17,1,70,0,5,0,2,0,-16,1,2, -0,-30,1,0,0,20,0,0,0,37,0,2,0,70,0,71,0,4,0,7,0,5,0,7,0,6,0,7,0,8,0,7, -0,-15,1,72,0,57,0,27,0,31,0,67,0,-66,1,12,0,-14,1,12,0,-47,1,32,0,-13,1,32,0,-12,1,32, -0,-11,1,36,0,79,0,73,0,-10,1,38,0,-9,1,62,0,-46,1,12,0,-8,1,7,0,7,1,7,0,-81,0,7, -0,8,1,4,0,-80,0,2,0,-7,1,2,0,-45,1,2,0,20,0,2,0,-6,1,7,0,-5,1,7,0,-4,1,7, -0,-3,1,2,0,-27,1,2,0,-26,1,2,0,-2,1,2,0,-1,1,4,0,70,0,2,0,23,0,2,0,98,0,2, -0,67,0,2,0,0,2,7,0,1,2,7,0,2,2,7,0,3,2,7,0,4,2,7,0,5,2,7,0,6,2,7, -0,7,2,7,0,8,2,7,0,9,2,7,0,10,2,0,0,11,2,0,0,12,2,64,0,13,2,64,0,14,2,64, -0,15,2,64,0,16,2,4,0,17,2,4,0,18,2,4,0,19,2,4,0,37,0,71,0,20,2,4,0,21,2,4, -0,22,2,70,0,23,2,70,0,24,2,74,0,39,0,27,0,31,0,67,0,-66,1,12,0,25,2,36,0,79,0,38, -0,-9,1,62,0,-46,1,75,0,26,2,76,0,27,2,77,0,28,2,78,0,29,2,79,0,30,2,80,0,31,2,81, -0,32,2,82,0,33,2,74,0,34,2,83,0,35,2,84,0,36,2,84,0,37,2,84,0,38,2,4,0,54,0,4, -0,39,2,4,0,40,2,4,0,41,2,4,0,42,2,4,0,-80,0,7,0,7,1,7,0,-81,0,7,0,8,1,7, -0,43,2,7,0,37,0,2,0,44,2,2,0,20,0,2,0,45,2,2,0,46,2,2,0,-45,1,2,0,47,2,85, -0,48,2,86,0,49,2,9,0,-94,0,77,0,8,0,9,0,50,2,7,0,51,2,4,0,52,2,0,0,20,0,0, -0,53,2,2,0,13,1,2,0,54,2,2,0,55,2,75,0,8,0,4,0,56,2,4,0,57,2,4,0,58,2,4, -0,59,2,0,0,37,0,0,0,-30,1,0,0,60,2,0,0,20,0,79,0,5,0,4,0,56,2,4,0,57,2,0, -0,61,2,0,0,62,2,2,0,20,0,87,0,2,0,4,0,63,2,7,0,-39,1,80,0,3,0,87,0,64,2,4, -0,65,2,4,0,20,0,78,0,6,0,7,0,66,2,2,0,67,2,0,0,20,0,0,0,-30,1,0,0,62,2,0, -0,68,2,81,0,4,0,0,0,-49,0,0,0,-73,0,0,0,-72,0,0,0,-71,0,88,0,6,0,46,0,50,2,0, -0,20,0,0,0,53,2,2,0,13,1,2,0,54,2,2,0,55,2,89,0,1,0,7,0,69,2,90,0,5,0,0, -0,-49,0,0,0,-73,0,0,0,-72,0,0,0,-71,0,4,0,37,0,82,0,1,0,7,0,70,2,83,0,2,0,4, -0,71,2,4,0,18,0,76,0,7,0,7,0,51,2,46,0,50,2,0,0,20,0,0,0,53,2,2,0,13,1,2, -0,54,2,2,0,55,2,91,0,1,0,7,0,72,2,92,0,1,0,4,0,73,2,93,0,1,0,0,0,74,2,94, -0,1,0,7,0,51,2,95,0,4,0,7,0,-49,0,7,0,-73,0,7,0,-72,0,7,0,-71,0,96,0,1,0,95, -0,52,2,97,0,5,0,4,0,75,2,4,0,76,2,0,0,20,0,0,0,-30,1,0,0,-74,0,98,0,2,0,4, -0,77,2,4,0,76,2,99,0,14,0,99,0,0,0,99,0,1,0,97,0,78,2,96,0,79,2,98,0,80,2,0, -0,81,2,12,0,82,2,12,0,83,2,100,0,84,2,4,0,54,0,4,0,40,2,4,0,39,2,4,0,37,0,78, -0,85,2,85,0,14,0,12,0,86,2,78,0,85,2,0,0,87,2,0,0,88,2,0,0,89,2,0,0,90,2,0, -0,91,2,0,0,92,2,0,0,93,2,0,0,20,0,84,0,36,2,84,0,38,2,2,0,94,2,0,0,95,2,86, -0,8,0,4,0,96,2,4,0,97,2,75,0,98,2,79,0,99,2,4,0,40,2,4,0,39,2,4,0,54,0,4, -0,37,0,101,0,6,0,101,0,0,0,101,0,1,0,4,0,18,0,4,0,13,1,0,0,17,0,0,0,100,2,102, -0,7,0,101,0,101,2,2,0,102,2,2,0,86,2,2,0,103,2,2,0,93,0,9,0,104,2,9,0,105,2,103, -0,3,0,101,0,101,2,32,0,-89,0,0,0,17,0,104,0,5,0,101,0,101,2,32,0,-89,0,0,0,17,0,2, -0,106,2,0,0,107,2,105,0,5,0,101,0,101,2,7,0,91,0,7,0,108,2,4,0,109,2,4,0,110,2,106, -0,5,0,101,0,101,2,32,0,111,2,0,0,72,0,4,0,13,1,4,0,20,0,107,0,13,0,101,0,101,2,32, -0,112,2,32,0,113,2,32,0,114,2,32,0,115,2,7,0,116,2,7,0,117,2,7,0,108,2,7,0,118,2,4, -0,119,2,4,0,120,2,4,0,93,0,4,0,121,2,108,0,5,0,101,0,101,2,2,0,122,2,2,0,20,0,7, -0,123,2,32,0,124,2,109,0,3,0,101,0,101,2,7,0,125,2,4,0,93,0,110,0,10,0,101,0,101,2,7, -0,126,2,4,0,127,2,4,0,37,0,2,0,93,0,2,0,-128,2,2,0,-127,2,2,0,-126,2,7,0,-125,2,0, -0,-124,2,111,0,3,0,101,0,101,2,7,0,37,0,4,0,18,0,112,0,11,0,101,0,101,2,51,0,-123,2,7, -0,-122,2,4,0,-121,2,0,0,-124,2,7,0,-120,2,4,0,-119,2,32,0,-118,2,0,0,-117,2,4,0,-116,2,4, -0,37,0,113,0,10,0,101,0,101,2,32,0,-115,2,46,0,-114,2,4,0,93,0,4,0,-113,2,7,0,-112,2,7, -0,-111,2,0,0,-117,2,4,0,-116,2,4,0,37,0,114,0,3,0,101,0,101,2,7,0,-110,2,4,0,-109,2,115, -0,5,0,101,0,101,2,7,0,-108,2,0,0,-124,2,2,0,20,0,2,0,-107,2,116,0,8,0,101,0,101,2,32, -0,-89,0,7,0,-108,2,7,0,-38,1,7,0,109,0,0,0,-124,2,2,0,20,0,2,0,18,0,117,0,21,0,101, -0,101,2,32,0,-106,2,0,0,-124,2,51,0,-123,2,32,0,-118,2,2,0,20,0,2,0,37,0,7,0,-105,2,7, -0,-104,2,7,0,-103,2,7,0,-5,1,7,0,-102,2,7,0,-101,2,7,0,-100,2,7,0,-99,2,4,0,-119,2,4, -0,-116,2,0,0,-117,2,7,0,-98,2,7,0,-97,2,7,0,43,0,118,0,7,0,101,0,101,2,2,0,-96,2,2, -0,-95,2,4,0,70,0,32,0,-89,0,7,0,-94,2,0,0,-124,2,119,0,9,0,101,0,101,2,32,0,-89,0,7, -0,-93,2,7,0,-92,2,7,0,-99,2,4,0,-91,2,4,0,-90,2,7,0,-89,2,0,0,17,0,120,0,1,0,101, -0,101,2,121,0,5,0,101,0,101,2,122,0,-88,2,123,0,-87,2,124,0,-86,2,125,0,-85,2,126,0,14,0,101, -0,101,2,78,0,-84,2,78,0,-83,2,78,0,-82,2,78,0,-81,2,78,0,-80,2,78,0,-79,2,75,0,-78,2,4, -0,-77,2,4,0,-76,2,2,0,-75,2,2,0,37,0,7,0,-74,2,127,0,-73,2,-128,0,3,0,101,0,101,2,-127, -0,-72,2,-126,0,-73,2,-125,0,4,0,101,0,101,2,32,0,-89,0,4,0,-71,2,4,0,37,0,-124,0,2,0,4, -0,-70,2,7,0,-39,1,-123,0,2,0,4,0,-127,0,4,0,-69,2,-122,0,20,0,101,0,101,2,32,0,-89,0,0, -0,-124,2,2,0,-68,2,2,0,-67,2,2,0,20,0,2,0,37,0,7,0,-66,2,7,0,-65,2,4,0,54,0,4, -0,-64,2,-123,0,-63,2,-124,0,-62,2,4,0,-61,2,4,0,-60,2,4,0,-59,2,4,0,-69,2,7,0,-58,2,7, -0,-57,2,7,0,-56,2,-121,0,8,0,101,0,101,2,-120,0,-55,2,-127,0,-72,2,4,0,-54,2,4,0,-53,2,4, -0,-52,2,2,0,20,0,2,0,57,0,-119,0,5,0,101,0,101,2,32,0,45,0,2,0,-51,2,2,0,20,0,2, -0,-50,2,-118,0,5,0,101,0,101,2,4,0,-49,2,2,0,20,0,2,0,-48,2,7,0,-47,2,-117,0,3,0,101, -0,101,2,-116,0,-46,2,125,0,-85,2,-115,0,10,0,101,0,101,2,32,0,-45,2,32,0,-44,2,0,0,-43,2,7, -0,-42,2,2,0,-41,2,2,0,-40,2,0,0,-39,2,0,0,-38,2,0,0,107,2,-114,0,9,0,101,0,101,2,32, -0,-37,2,0,0,-43,2,7,0,-36,2,7,0,-35,2,0,0,13,1,0,0,122,2,0,0,-34,2,0,0,37,0,-113, -0,24,0,27,0,31,0,2,0,-29,1,2,0,-28,1,2,0,-33,2,2,0,20,0,2,0,-32,2,2,0,-31,2,2, -0,-30,2,2,0,70,0,0,0,-29,2,0,0,-28,2,0,0,-27,2,0,0,18,0,4,0,37,0,7,0,-26,2,7, -0,-25,2,7,0,-24,2,7,0,-23,2,7,0,-22,2,7,0,-21,2,34,0,-20,2,36,0,79,0,38,0,-9,1,80, -0,31,2,-112,0,3,0,-112,0,0,0,-112,0,1,0,0,0,17,0,67,0,3,0,7,0,-19,2,4,0,20,0,4, -0,37,0,32,0,111,0,27,0,31,0,2,0,18,0,2,0,-18,2,4,0,-17,2,4,0,-16,2,4,0,-15,2,0, -0,-14,2,32,0,38,0,32,0,-13,2,32,0,-12,2,32,0,-11,2,32,0,-10,2,36,0,79,0,73,0,-10,1,67, -0,-66,1,-111,0,-9,2,-111,0,-8,2,-110,0,-7,2,9,0,2,0,12,0,-6,2,12,0,25,2,12,0,-47,1,12, -0,-5,2,12,0,-4,2,62,0,-46,1,7,0,7,1,7,0,-3,2,7,0,-2,2,7,0,-81,0,7,0,-1,2,7, -0,8,1,7,0,0,3,7,0,1,3,7,0,-93,2,7,0,2,3,7,0,-45,0,4,0,3,3,2,0,20,0,2, -0,4,3,2,0,5,3,2,0,6,3,2,0,7,3,2,0,8,3,2,0,9,3,2,0,10,3,2,0,11,3,2, -0,12,3,2,0,13,3,2,0,14,3,4,0,15,3,4,0,16,3,4,0,17,3,4,0,18,3,7,0,19,3,7, -0,20,3,7,0,21,3,7,0,22,3,7,0,23,3,7,0,24,3,7,0,25,3,7,0,26,3,7,0,27,3,7, -0,28,3,7,0,29,3,7,0,30,3,0,0,31,3,0,0,32,3,0,0,-45,1,0,0,33,3,0,0,34,3,0, -0,35,3,7,0,36,3,7,0,37,3,39,0,125,0,12,0,38,3,12,0,39,3,12,0,40,3,12,0,41,3,7, -0,42,3,2,0,71,2,2,0,43,3,7,0,52,2,4,0,44,3,4,0,45,3,-109,0,46,3,2,0,47,3,2, -0,-38,0,7,0,48,3,12,0,49,3,12,0,50,3,12,0,51,3,12,0,52,3,-108,0,53,3,-107,0,54,3,63, -0,55,3,2,0,56,3,2,0,57,3,2,0,58,3,2,0,59,3,7,0,44,2,2,0,60,3,2,0,61,3,-116, -0,62,3,-127,0,63,3,-127,0,64,3,4,0,65,3,4,0,66,3,4,0,67,3,4,0,70,0,9,0,-94,0,12, -0,68,3,-106,0,14,0,-106,0,0,0,-106,0,1,0,32,0,38,0,7,0,-93,2,7,0,9,1,7,0,-92,2,7, -0,-99,2,0,0,17,0,4,0,-91,2,4,0,-90,2,4,0,69,3,2,0,18,0,2,0,70,3,7,0,-89,2,-108, -0,36,0,2,0,71,3,2,0,72,3,2,0,20,0,2,0,-99,2,7,0,73,3,7,0,74,3,7,0,75,3,7, -0,76,3,7,0,77,3,7,0,78,3,7,0,79,3,7,0,80,3,7,0,81,3,7,0,82,3,7,0,83,3,7, -0,84,3,7,0,85,3,7,0,86,3,7,0,87,3,7,0,88,3,7,0,89,3,7,0,90,3,7,0,91,3,7, -0,92,3,7,0,93,3,7,0,94,3,7,0,95,3,7,0,96,3,2,0,97,3,2,0,98,3,2,0,99,3,2, -0,100,3,51,0,-88,0,-105,0,101,3,7,0,102,3,4,0,110,2,125,0,5,0,4,0,20,0,4,0,103,3,4, -0,104,3,4,0,105,3,4,0,106,3,-104,0,1,0,7,0,-31,1,-109,0,30,0,4,0,20,0,7,0,107,3,7, -0,108,3,7,0,109,3,4,0,110,3,4,0,111,3,4,0,112,3,4,0,113,3,7,0,114,3,7,0,115,3,7, -0,116,3,7,0,117,3,7,0,118,3,7,0,119,3,7,0,120,3,7,0,121,3,7,0,122,3,7,0,123,3,7, -0,124,3,7,0,125,3,7,0,126,3,7,0,127,3,7,0,-128,3,7,0,-127,3,7,0,-126,3,7,0,-125,3,4, -0,-124,3,4,0,-123,3,7,0,-122,3,7,0,27,3,-107,0,49,0,-120,0,-121,3,4,0,-120,3,4,0,-119,3,-103, -0,-118,3,-102,0,-117,3,0,0,37,0,0,0,-116,3,2,0,-115,3,7,0,-114,3,0,0,-113,3,7,0,-112,3,7, -0,-111,3,7,0,-110,3,7,0,-109,3,7,0,-108,3,7,0,-107,3,7,0,-106,3,7,0,-105,3,7,0,-104,3,2, -0,-103,3,0,0,-102,3,2,0,-101,3,7,0,-100,3,7,0,-99,3,0,0,-98,3,4,0,-126,0,4,0,-97,3,4, -0,-96,3,2,0,-95,3,2,0,-94,3,-104,0,-93,3,4,0,-92,3,4,0,81,0,7,0,-91,3,7,0,-90,3,7, -0,-89,3,7,0,-88,3,2,0,-87,3,2,0,-86,3,2,0,-85,3,2,0,-84,3,2,0,-83,3,2,0,-82,3,2, -0,-81,3,2,0,-80,3,-101,0,-79,3,7,0,-78,3,7,0,-77,3,125,0,-76,3,-116,0,48,0,2,0,18,0,2, -0,-75,3,2,0,-74,3,2,0,-73,3,7,0,-72,3,2,0,-71,3,2,0,-70,3,7,0,-69,3,2,0,-68,3,2, -0,-67,3,7,0,-66,3,7,0,-65,3,7,0,-64,3,7,0,-63,3,7,0,-62,3,7,0,-61,3,4,0,-60,3,7, -0,-59,3,7,0,-58,3,7,0,-57,3,74,0,-56,3,74,0,-55,3,74,0,-54,3,0,0,-53,3,7,0,-52,3,7, -0,-51,3,36,0,79,0,2,0,-50,3,0,0,-49,3,0,0,-48,3,7,0,-47,3,4,0,-46,3,7,0,-45,3,7, -0,-44,3,4,0,-43,3,4,0,20,0,7,0,-42,3,7,0,-41,3,7,0,-40,3,78,0,-39,3,7,0,-38,3,7, -0,-37,3,7,0,-36,3,7,0,-35,3,7,0,-34,3,7,0,-33,3,7,0,-32,3,4,0,-31,3,-100,0,71,0,27, -0,31,0,2,0,-79,0,2,0,14,1,2,0,47,1,2,0,-30,3,7,0,-29,3,7,0,-28,3,7,0,-27,3,7, -0,-26,3,7,0,-25,3,7,0,-24,3,7,0,-23,3,7,0,-22,3,7,0,84,1,7,0,86,1,7,0,85,1,7, -0,-21,3,4,0,-20,3,7,0,-19,3,7,0,-18,3,7,0,-17,3,7,0,-16,3,7,0,-15,3,7,0,-14,3,7, -0,-13,3,2,0,-12,3,2,0,13,1,2,0,-11,3,2,0,-10,3,2,0,-9,3,2,0,-8,3,2,0,-7,3,2, -0,-6,3,7,0,-5,3,7,0,-4,3,7,0,-3,3,7,0,-2,3,7,0,-1,3,7,0,0,4,7,0,1,4,7, -0,2,4,7,0,3,4,7,0,4,4,7,0,5,4,7,0,6,4,2,0,7,4,2,0,8,4,2,0,9,4,2, -0,10,4,7,0,11,4,7,0,12,4,7,0,13,4,7,0,14,4,2,0,15,4,2,0,16,4,2,0,17,4,2, -0,18,4,7,0,19,4,7,0,20,4,7,0,21,4,7,0,22,4,2,0,23,4,2,0,24,4,2,0,25,4,2, -0,43,0,7,0,26,4,7,0,27,4,36,0,79,0,50,0,77,1,30,0,-103,0,39,0,125,0,-99,0,16,0,2, -0,28,4,2,0,29,4,2,0,30,4,2,0,20,0,2,0,31,4,2,0,32,4,2,0,33,4,2,0,34,4,2, -0,35,4,2,0,36,4,2,0,37,4,2,0,38,4,4,0,39,4,7,0,40,4,7,0,41,4,7,0,42,4,-98, -0,8,0,-98,0,0,0,-98,0,1,0,4,0,3,3,4,0,43,4,4,0,20,0,2,0,44,4,2,0,45,4,32, -0,-89,0,-97,0,13,0,9,0,46,4,9,0,47,4,4,0,48,4,4,0,49,4,4,0,50,4,4,0,51,4,4, -0,52,4,4,0,53,4,4,0,54,4,4,0,55,4,4,0,56,4,4,0,37,0,0,0,57,4,-96,0,5,0,9, -0,58,4,9,0,59,4,4,0,60,4,4,0,70,0,0,0,61,4,-95,0,13,0,4,0,18,0,4,0,62,4,4, -0,63,4,4,0,64,4,4,0,65,4,4,0,66,4,4,0,93,0,4,0,67,4,4,0,68,4,4,0,69,4,4, -0,70,4,4,0,71,4,26,0,30,0,-94,0,4,0,4,0,72,4,7,0,73,4,2,0,20,0,2,0,68,2,-93, -0,11,0,-93,0,0,0,-93,0,1,0,0,0,17,0,62,0,74,4,63,0,75,4,4,0,3,3,4,0,76,4,4, -0,77,4,4,0,37,0,4,0,78,4,4,0,79,4,-92,0,-126,0,-97,0,80,4,-96,0,81,4,-95,0,82,4,4, -0,83,4,4,0,-126,0,4,0,-97,3,4,0,84,4,4,0,85,4,4,0,86,4,4,0,87,4,2,0,20,0,2, -0,88,4,7,0,20,3,7,0,89,4,7,0,90,4,7,0,91,4,7,0,92,4,7,0,93,4,2,0,94,4,2, -0,95,4,2,0,96,4,2,0,97,4,2,0,-39,0,2,0,98,4,2,0,99,4,2,0,100,3,2,0,100,4,2, -0,101,4,2,0,34,1,2,0,109,0,2,0,102,4,2,0,103,4,2,0,104,4,2,0,105,4,2,0,106,4,2, -0,107,4,2,0,108,4,2,0,109,4,2,0,110,4,2,0,35,1,2,0,111,4,2,0,112,4,2,0,113,4,2, -0,114,4,4,0,115,4,4,0,13,1,2,0,116,4,2,0,117,4,2,0,118,4,2,0,119,4,2,0,120,4,2, -0,121,4,24,0,122,4,24,0,123,4,23,0,124,4,12,0,125,4,2,0,126,4,2,0,37,0,7,0,127,4,7, -0,-128,4,7,0,-127,4,7,0,-126,4,7,0,-125,4,7,0,-124,4,7,0,-123,4,7,0,-122,4,7,0,-121,4,2, -0,-120,4,2,0,-119,4,2,0,-118,4,2,0,-117,4,2,0,-116,4,2,0,-115,4,7,0,-114,4,7,0,-113,4,7, -0,-112,4,2,0,-111,4,2,0,-110,4,2,0,-109,4,2,0,-108,4,2,0,-107,4,2,0,-106,4,2,0,-105,4,2, -0,-104,4,2,0,-103,4,2,0,-102,4,4,0,-101,4,4,0,-100,4,4,0,-99,4,4,0,-98,4,4,0,-97,4,7, -0,-96,4,4,0,-95,4,4,0,-94,4,4,0,-93,4,4,0,-92,4,7,0,-91,4,7,0,-90,4,7,0,-89,4,7, -0,-88,4,7,0,-87,4,7,0,-86,4,7,0,-85,4,7,0,-84,4,7,0,-83,4,0,0,-82,4,0,0,-81,4,4, -0,-80,4,2,0,-79,4,2,0,12,1,0,0,-78,4,7,0,-77,4,7,0,-76,4,4,0,-75,4,4,0,-74,4,7, -0,-73,4,7,0,-72,4,2,0,-71,4,2,0,-70,4,7,0,-69,4,2,0,-68,4,2,0,-67,4,4,0,-66,4,2, -0,-65,4,2,0,-64,4,2,0,-63,4,2,0,-62,4,7,0,-61,4,7,0,70,0,42,0,-60,4,-91,0,9,0,-91, -0,0,0,-91,0,1,0,0,0,17,0,2,0,-59,4,2,0,-58,4,2,0,-57,4,2,0,43,0,7,0,-56,4,7, -0,70,0,-90,0,5,0,7,0,-55,4,0,0,18,0,0,0,43,0,0,0,70,0,0,0,12,1,-89,0,5,0,-89, -0,0,0,-89,0,1,0,4,0,-54,4,0,0,-53,4,4,0,20,0,-88,0,5,0,-87,0,-52,4,2,0,20,0,2, -0,-51,4,2,0,-50,4,2,0,-49,4,-86,0,4,0,2,0,109,0,2,0,-122,2,2,0,-48,4,2,0,-47,4,-85, -0,7,0,2,0,20,0,2,0,-46,4,2,0,-45,4,2,0,-44,4,-86,0,-43,4,7,0,-42,4,4,0,-41,4,-84, -0,4,0,-84,0,0,0,-84,0,1,0,0,0,-40,4,7,0,-39,4,-83,0,56,0,2,0,-38,4,2,0,-37,4,7, -0,-36,4,7,0,-35,4,2,0,-48,4,2,0,-34,4,7,0,-33,4,7,0,-32,4,2,0,-31,4,2,0,-30,4,2, -0,-29,4,2,0,-28,4,7,0,-27,4,7,0,-26,4,7,0,-25,4,7,0,37,0,2,0,-24,4,2,0,-23,4,2, -0,-22,4,2,0,-21,4,-88,0,-20,4,-85,0,-19,4,7,0,-18,4,7,0,-17,4,0,0,-16,4,0,0,-15,4,0, -0,-14,4,0,0,-13,4,0,0,-12,4,0,0,-11,4,2,0,-10,4,7,0,-9,4,7,0,-8,4,7,0,-7,4,7, -0,-6,4,7,0,-5,4,7,0,-4,4,7,0,-3,4,7,0,-2,4,7,0,-1,4,7,0,0,5,2,0,1,5,0, -0,2,5,0,0,3,5,0,0,4,5,0,0,5,5,32,0,6,5,0,0,7,5,0,0,8,5,0,0,9,5,0, -0,10,5,0,0,11,5,0,0,12,5,0,0,13,5,0,0,14,5,0,0,15,5,-82,0,6,0,2,0,109,0,0, -0,-122,2,0,0,16,5,0,0,17,5,0,0,20,0,0,0,-74,0,-81,0,26,0,-80,0,18,5,50,0,77,1,60, -0,19,5,-82,0,20,5,-82,0,21,5,-82,0,22,5,-82,0,23,5,-82,0,24,5,-82,0,25,5,-82,0,26,5,7, -0,27,5,2,0,28,5,2,0,47,1,2,0,29,5,2,0,1,2,0,0,30,5,0,0,31,5,0,0,32,5,0, -0,33,5,0,0,93,0,0,0,34,5,0,0,35,5,0,0,36,5,0,0,37,5,0,0,38,5,0,0,-74,0,-79, -0,43,0,27,0,31,0,32,0,39,5,-100,0,40,5,-79,0,41,5,46,0,-47,0,12,0,42,5,-98,0,43,5,7, -0,44,5,7,0,45,5,7,0,46,5,7,0,47,5,4,0,3,3,7,0,48,5,2,0,49,5,2,0,50,5,2, -0,51,5,2,0,52,5,2,0,53,5,2,0,54,5,2,0,55,5,2,0,5,1,57,0,1,1,9,0,56,5,-99, -0,57,5,-90,0,58,5,-83,0,59,5,-92,0,-73,0,-94,0,60,5,39,0,125,0,12,0,103,0,12,0,61,5,2, -0,62,5,2,0,63,5,2,0,64,5,2,0,65,5,-78,0,66,5,2,0,67,5,2,0,68,5,2,0,64,1,2, -0,-38,0,-81,0,69,5,4,0,70,5,4,0,37,0,-77,0,9,0,46,0,-47,0,45,0,0,1,7,0,8,2,7, -0,9,2,7,0,109,0,7,0,71,5,7,0,72,5,2,0,73,5,2,0,74,5,-76,0,75,0,-75,0,0,0,-75, -0,1,0,4,0,75,5,7,0,76,5,-74,0,77,5,2,0,78,5,7,0,79,5,7,0,80,5,7,0,81,5,7, -0,82,5,7,0,83,5,7,0,84,5,7,0,85,5,7,0,20,1,7,0,86,5,4,0,87,5,2,0,88,5,2, -0,17,5,32,0,39,5,32,0,89,5,-77,0,90,5,-76,0,91,5,-73,0,92,5,-72,0,93,5,-71,0,94,5,0, -0,95,5,2,0,30,4,2,0,96,5,4,0,3,3,4,0,97,5,2,0,98,5,2,0,99,5,2,0,100,5,0, -0,101,5,0,0,43,0,7,0,115,0,7,0,102,5,7,0,103,5,7,0,104,5,7,0,105,5,7,0,106,5,7, -0,107,5,7,0,108,5,7,0,-82,0,7,0,44,5,2,0,109,5,2,0,110,5,2,0,111,5,2,0,112,5,2, -0,-119,0,2,0,29,5,2,0,113,5,2,0,114,5,2,0,115,5,2,0,116,5,7,0,117,5,7,0,118,5,67, -0,119,5,12,0,120,5,2,0,121,5,2,0,53,2,2,0,122,5,2,0,20,0,2,0,123,5,2,0,124,5,2, -0,125,5,0,0,126,5,0,0,127,5,9,0,-128,5,-70,0,-127,5,7,0,-126,5,2,0,-125,5,2,0,-124,5,2, -0,53,5,2,0,54,5,-69,0,19,0,24,0,36,0,24,0,64,0,23,0,-123,5,23,0,-122,5,23,0,-121,5,7, -0,-120,5,7,0,-119,5,7,0,-118,5,7,0,-117,5,2,0,-116,5,2,0,-115,5,2,0,-114,5,2,0,-113,5,2, -0,-112,5,2,0,-111,5,4,0,20,0,7,0,-110,5,2,0,99,5,0,0,107,2,-75,0,6,0,-75,0,0,0,-75, -0,1,0,4,0,75,5,7,0,76,5,-74,0,77,5,2,0,78,5,-68,0,6,0,-75,0,0,0,-75,0,1,0,4, -0,75,5,7,0,76,5,-74,0,77,5,2,0,78,5,-67,0,27,0,-75,0,0,0,-75,0,1,0,4,0,75,5,7, -0,76,5,-74,0,77,5,2,0,78,5,4,0,-109,5,4,0,70,0,-69,0,-108,5,9,0,-107,5,12,0,-106,5,36, -0,79,0,27,0,80,0,0,0,-105,5,0,0,-104,5,0,0,-103,5,2,0,-102,5,2,0,-101,5,2,0,-100,5,2, -0,-99,5,2,0,65,0,2,0,46,0,2,0,-119,0,2,0,-98,5,4,0,20,0,7,0,-97,5,24,0,36,0,-66, -0,29,0,-75,0,0,0,-75,0,1,0,4,0,75,5,7,0,76,5,-74,0,77,5,-73,0,92,5,2,0,78,5,2, -0,-96,5,2,0,-95,5,2,0,-94,5,2,0,-93,5,-69,0,-108,5,2,0,-92,5,2,0,-119,0,2,0,-101,5,2, -0,-91,5,9,0,-90,5,2,0,29,5,0,0,-89,5,0,0,-88,5,2,0,-87,5,2,0,-86,5,2,0,12,3,2, -0,-85,5,2,0,-84,5,0,0,37,0,0,0,20,0,0,0,47,1,0,0,-83,5,-65,0,16,0,-75,0,0,0,-75, -0,1,0,4,0,75,5,7,0,76,5,-74,0,77,5,2,0,78,5,-69,0,-108,5,7,0,8,2,7,0,9,2,2, -0,-92,5,2,0,-82,5,2,0,-81,5,2,0,-80,5,4,0,20,0,7,0,71,5,-70,0,-127,5,-64,0,33,0,-75, -0,0,0,-75,0,1,0,4,0,75,5,7,0,76,5,-74,0,77,5,2,0,78,5,-63,0,-79,5,4,0,-78,5,0, -0,-77,5,0,0,-76,5,0,0,-75,5,2,0,18,0,2,0,-74,5,2,0,20,0,2,0,-73,5,2,0,-72,5,2, -0,-71,5,2,0,-70,5,2,0,43,0,4,0,70,0,0,0,-69,5,-62,0,-68,5,2,0,-67,5,2,0,-66,5,2, -0,-65,5,2,0,-48,0,9,0,-64,5,9,0,-63,5,9,0,-62,5,9,0,-61,5,9,0,-60,5,2,0,-59,5,0, -0,-58,5,-61,0,23,0,-75,0,0,0,-75,0,1,0,4,0,75,5,7,0,76,5,-74,0,77,5,2,0,78,5,-69, -0,-108,5,12,0,-57,5,2,0,-101,5,2,0,-56,5,2,0,20,0,2,0,57,0,9,0,-90,5,12,0,-55,5,-60, -0,-54,5,0,0,-53,5,-59,0,-52,5,4,0,-51,5,4,0,-50,5,2,0,18,0,2,0,-49,5,2,0,-48,5,2, -0,-47,5,-58,0,29,0,-75,0,0,0,-75,0,1,0,4,0,75,5,7,0,76,5,-74,0,77,5,2,0,78,5,-69, -0,-108,5,46,0,-114,2,45,0,0,1,60,0,19,5,2,0,13,1,2,0,-119,0,2,0,-46,5,2,0,-45,5,4, -0,20,0,2,0,49,5,2,0,-44,5,2,0,-98,5,2,0,-101,5,7,0,71,5,0,0,-43,5,0,0,-42,5,0, -0,-41,5,0,0,-40,5,7,0,8,2,7,0,9,2,7,0,-39,5,7,0,-38,5,-70,0,-127,5,-57,0,11,0,-75, -0,0,0,-75,0,1,0,4,0,75,5,7,0,76,5,-74,0,77,5,2,0,78,5,2,0,-119,0,2,0,-98,5,2, -0,-37,5,2,0,20,0,-69,0,-108,5,-56,0,24,0,-75,0,0,0,-75,0,1,0,4,0,75,5,7,0,76,5,-74, -0,77,5,2,0,78,5,42,0,-36,5,4,0,-35,5,4,0,-34,5,2,0,93,0,2,0,-119,0,4,0,-33,5,4, -0,-32,5,4,0,-31,5,4,0,-30,5,4,0,-29,5,4,0,-28,5,4,0,-27,5,4,0,-26,5,7,0,-25,5,23, -0,-24,5,23,0,-23,5,4,0,-22,5,4,0,-21,5,-55,0,10,0,27,0,31,0,9,0,-20,5,9,0,-19,5,9, -0,-18,5,9,0,-17,5,9,0,-16,5,4,0,93,0,4,0,-15,5,0,0,-14,5,0,0,-13,5,-54,0,10,0,-75, -0,0,0,-75,0,1,0,4,0,75,5,7,0,76,5,-74,0,77,5,-55,0,-12,5,2,0,93,0,2,0,-119,0,4, -0,43,0,9,0,-11,5,-53,0,8,0,-75,0,0,0,-75,0,1,0,4,0,75,5,7,0,76,5,-74,0,77,5,-69, -0,-108,5,4,0,20,0,4,0,-10,5,-52,0,21,0,-75,0,0,0,-75,0,1,0,4,0,75,5,7,0,76,5,-74, -0,77,5,2,0,78,5,-69,0,-108,5,27,0,-9,5,27,0,80,0,2,0,20,0,2,0,-119,0,7,0,-8,5,9, -0,-7,5,7,0,8,2,7,0,9,2,57,0,1,1,57,0,-6,5,4,0,-5,5,2,0,-89,5,2,0,37,0,-70, -0,-127,5,-51,0,42,0,-75,0,0,0,-75,0,1,0,4,0,75,5,7,0,76,5,-74,0,77,5,2,0,78,5,-69, -0,-108,5,-50,0,-4,5,0,0,-77,5,0,0,-76,5,0,0,-75,5,2,0,18,0,2,0,-66,5,2,0,20,0,2, -0,-73,5,9,0,-7,5,4,0,-3,5,4,0,-2,5,4,0,-1,5,4,0,0,6,23,0,1,6,23,0,2,6,7, -0,3,6,7,0,4,6,7,0,5,6,7,0,-8,5,2,0,-67,5,2,0,-48,0,2,0,102,1,2,0,6,6,2, -0,37,0,2,0,43,0,2,0,7,6,2,0,8,6,9,0,-64,5,9,0,-63,5,9,0,-62,5,9,0,-61,5,9, -0,-60,5,2,0,-59,5,0,0,-58,5,56,0,9,6,-49,0,20,0,0,0,10,6,0,0,11,6,0,0,12,6,0, -0,13,6,0,0,14,6,0,0,15,6,0,0,16,6,0,0,17,6,0,0,18,6,0,0,19,6,0,0,20,6,0, -0,21,6,0,0,22,6,0,0,23,6,0,0,24,6,0,0,25,6,0,0,26,6,0,0,27,6,0,0,68,2,0, -0,28,6,-48,0,54,0,0,0,29,6,0,0,20,6,0,0,21,6,0,0,30,6,0,0,31,6,0,0,32,6,0, -0,33,6,0,0,34,6,0,0,35,6,0,0,36,6,0,0,37,6,0,0,38,6,0,0,39,6,0,0,40,6,0, -0,41,6,0,0,42,6,0,0,43,6,0,0,44,6,0,0,45,6,0,0,46,6,0,0,47,6,0,0,48,6,0, -0,49,6,0,0,50,6,0,0,51,6,0,0,52,6,0,0,53,6,0,0,54,6,0,0,55,6,0,0,56,6,0, -0,57,6,0,0,58,6,0,0,95,0,0,0,59,6,0,0,60,6,0,0,61,6,0,0,62,6,0,0,63,6,0, -0,64,6,0,0,65,6,0,0,66,6,0,0,67,6,0,0,68,6,0,0,69,6,0,0,70,6,0,0,71,6,0, -0,72,6,0,0,73,6,0,0,74,6,0,0,75,6,0,0,76,6,0,0,77,6,0,0,78,6,0,0,79,6,-47, -0,5,0,0,0,80,6,0,0,37,6,0,0,39,6,2,0,20,0,2,0,37,0,-46,0,22,0,-46,0,0,0,-46, -0,1,0,0,0,17,0,-49,0,81,6,-48,0,82,6,-48,0,83,6,-48,0,84,6,-48,0,85,6,-48,0,86,6,-48, -0,87,6,-48,0,88,6,-48,0,89,6,-48,0,90,6,-48,0,91,6,-48,0,92,6,-48,0,93,6,-48,0,94,6,-48, -0,95,6,-48,0,96,6,-47,0,97,6,0,0,98,6,0,0,99,6,-45,0,5,0,4,0,20,0,4,0,37,0,7, -0,52,2,7,0,100,6,7,0,-31,1,-44,0,66,0,4,0,20,0,4,0,101,6,4,0,102,6,0,0,103,6,0, -0,104,6,0,0,105,6,0,0,106,6,0,0,107,6,0,0,108,6,0,0,109,6,0,0,110,6,0,0,111,6,2, -0,112,6,2,0,113,6,4,0,114,6,4,0,115,6,4,0,116,6,4,0,117,6,2,0,118,6,2,0,119,6,2, -0,120,6,2,0,121,6,4,0,122,6,4,0,123,6,2,0,124,6,2,0,125,6,2,0,126,6,2,0,127,6,0, -0,-128,6,12,0,-127,6,2,0,-126,6,2,0,-125,6,2,0,-124,6,2,0,-123,6,2,0,-122,6,2,0,-121,6,2, -0,-120,6,2,0,-119,6,-45,0,-118,6,2,0,-117,6,2,0,-116,6,2,0,-115,6,2,0,-114,6,4,0,-113,6,4, -0,-112,6,4,0,-111,6,4,0,-110,6,2,0,-109,6,2,0,-108,6,2,0,-107,6,2,0,-106,6,2,0,-105,6,2, -0,-104,6,2,0,-103,6,2,0,-102,6,2,0,-101,6,2,0,-100,6,2,0,-99,6,2,0,37,0,0,0,-98,6,0, -0,-97,6,0,0,-96,6,7,0,-95,6,2,0,55,5,2,0,-94,6,54,0,-93,6,-43,0,18,0,27,0,31,0,12, -0,-92,6,12,0,-91,6,12,0,-90,6,-79,0,-89,6,2,0,-105,2,2,0,-88,6,2,0,-104,2,2,0,-87,6,2, -0,-86,6,2,0,-85,6,2,0,-84,6,2,0,-83,6,2,0,-82,6,2,0,37,0,2,0,-81,6,2,0,-80,6,2, -0,-79,6,-42,0,5,0,-42,0,0,0,-42,0,1,0,-42,0,-78,6,13,0,-77,6,4,0,20,0,-41,0,7,0,-41, -0,0,0,-41,0,1,0,-42,0,-76,6,-42,0,-75,6,2,0,123,4,2,0,20,0,4,0,37,0,-40,0,17,0,-40, -0,0,0,-40,0,1,0,0,0,-74,6,0,0,-73,6,0,0,-72,6,2,0,-71,6,2,0,-70,6,2,0,-86,6,2, -0,-85,6,2,0,20,0,2,0,70,3,2,0,-69,6,2,0,-68,6,2,0,-67,6,2,0,-66,6,4,0,-65,6,-40, -0,-64,6,-74,0,30,0,-74,0,0,0,-74,0,1,0,-42,0,-76,6,-42,0,-75,6,-42,0,-63,6,-42,0,-62,6,-43, -0,-61,6,7,0,-60,6,23,0,52,0,23,0,-59,6,23,0,-58,6,2,0,-57,6,2,0,-56,6,2,0,-55,6,0, -0,75,5,0,0,-54,6,2,0,-53,6,2,0,-52,6,0,0,-51,6,0,0,-50,6,0,0,-49,6,0,0,-48,6,2, -0,-47,6,2,0,-46,6,2,0,-45,6,2,0,20,0,39,0,125,0,12,0,-44,6,12,0,-43,6,12,0,-42,6,-39, -0,11,0,0,0,-41,6,2,0,-40,6,2,0,-39,6,2,0,-38,6,2,0,-37,6,2,0,-36,6,2,0,107,4,9, -0,-35,6,9,0,-34,6,4,0,-33,6,4,0,-32,6,-38,0,1,0,0,0,-31,6,-37,0,8,0,56,0,-30,6,56, -0,-29,6,-37,0,-28,6,-37,0,-27,6,-37,0,-26,6,2,0,-123,0,2,0,20,0,4,0,-25,6,-36,0,4,0,4, -0,-35,5,4,0,-24,6,4,0,-31,5,4,0,-23,6,-35,0,2,0,4,0,-22,6,4,0,-21,6,-34,0,9,0,7, -0,-20,6,7,0,-19,6,7,0,-18,6,4,0,20,0,4,0,13,1,7,0,-19,3,7,0,-17,6,4,0,37,0,-33, -0,-16,6,-32,0,6,0,0,0,-15,6,0,0,-75,5,48,0,-116,0,2,0,109,0,2,0,111,4,4,0,37,0,-31, -0,21,0,-31,0,0,0,-31,0,1,0,4,0,57,0,4,0,23,0,4,0,28,0,4,0,-14,6,4,0,-13,6,4, -0,-12,6,-38,0,-11,6,0,0,-15,6,4,0,-10,6,4,0,-9,6,-32,0,-12,2,-36,0,-8,6,-35,0,-7,6,-34, -0,-6,6,-37,0,-5,6,-37,0,-4,6,-37,0,-3,6,56,0,-2,6,56,0,-1,6,-30,0,12,0,0,0,-68,1,9, -0,-62,0,0,0,-61,0,4,0,-58,0,4,0,-50,0,9,0,-57,0,7,0,-55,0,7,0,-54,0,9,0,0,7,9, -0,1,7,9,0,-53,0,9,0,-51,0,-29,0,43,0,-29,0,0,0,-29,0,1,0,9,0,2,7,9,0,26,0,0, -0,27,0,4,0,20,0,4,0,18,0,4,0,23,0,4,0,91,0,4,0,3,7,4,0,4,7,4,0,-13,6,4, -0,-12,6,4,0,5,7,4,0,-39,0,4,0,6,7,4,0,7,7,7,0,8,7,7,0,9,7,4,0,-126,0,4, -0,10,7,-31,0,11,7,36,0,79,0,-79,0,-89,6,48,0,-116,0,7,0,12,7,7,0,13,7,-30,0,2,1,-29, -0,14,7,-29,0,15,7,-29,0,16,7,12,0,17,7,-28,0,18,7,-27,0,19,7,7,0,20,7,7,0,21,7,4, -0,-84,6,7,0,22,7,9,0,23,7,4,0,24,7,4,0,25,7,4,0,26,7,7,0,27,7,-26,0,4,0,-26, -0,0,0,-26,0,1,0,12,0,28,7,-29,0,29,7,-25,0,6,0,12,0,30,7,12,0,17,7,12,0,31,7,2, -0,20,0,2,0,37,0,4,0,57,0,-24,0,4,0,7,0,32,7,7,0,112,0,2,0,33,7,2,0,34,7,-23, -0,6,0,7,0,35,7,7,0,36,7,7,0,37,7,7,0,38,7,4,0,39,7,4,0,40,7,-22,0,12,0,7, -0,41,7,7,0,42,7,7,0,43,7,7,0,44,7,7,0,45,7,7,0,46,7,7,0,47,7,7,0,48,7,7, -0,49,7,7,0,50,7,4,0,-110,2,4,0,51,7,-21,0,2,0,7,0,-55,4,7,0,37,0,-20,0,7,0,7, -0,52,7,7,0,53,7,4,0,93,0,4,0,108,2,4,0,54,7,4,0,55,7,4,0,37,0,-19,0,6,0,-19, -0,0,0,-19,0,1,0,2,0,18,0,2,0,20,0,2,0,56,7,2,0,57,0,-18,0,8,0,-18,0,0,0,-18, -0,1,0,2,0,18,0,2,0,20,0,2,0,56,7,2,0,57,0,7,0,23,0,7,0,-126,0,-17,0,45,0,-17, -0,0,0,-17,0,1,0,2,0,18,0,2,0,20,0,2,0,56,7,2,0,-43,0,2,0,-103,3,2,0,57,7,7, -0,58,7,7,0,92,0,7,0,-97,2,4,0,59,7,4,0,81,0,4,0,110,2,7,0,60,7,7,0,61,7,7, -0,62,7,7,0,63,7,7,0,64,7,7,0,65,7,7,0,-100,2,7,0,-1,0,7,0,66,7,7,0,67,7,7, -0,37,0,7,0,68,7,7,0,69,7,7,0,70,7,2,0,71,7,2,0,72,7,2,0,73,7,2,0,74,7,2, -0,75,7,2,0,76,7,2,0,77,7,2,0,78,7,2,0,123,5,2,0,79,7,2,0,-47,1,2,0,80,7,0, -0,81,7,0,0,82,7,7,0,-45,0,-16,0,83,7,63,0,-95,1,-15,0,16,0,-15,0,0,0,-15,0,1,0,2, -0,18,0,2,0,20,0,2,0,56,7,2,0,-43,0,7,0,-105,2,7,0,-104,2,7,0,-103,2,7,0,-5,1,7, -0,-102,2,7,0,-101,2,7,0,84,7,7,0,-100,2,7,0,-98,2,7,0,-97,2,-59,0,5,0,2,0,18,0,2, -0,-25,6,2,0,20,0,2,0,85,7,27,0,-9,5,-60,0,3,0,4,0,69,0,4,0,86,7,-59,0,2,0,-14, -0,12,0,-14,0,0,0,-14,0,1,0,2,0,18,0,2,0,20,0,2,0,31,3,2,0,-32,1,7,0,5,0,7, -0,6,0,7,0,87,7,7,0,88,7,27,0,-9,5,12,0,89,7,-13,0,11,0,-13,0,0,0,-13,0,1,0,0, -0,17,0,2,0,18,0,2,0,90,7,4,0,22,0,4,0,91,7,2,0,20,0,2,0,37,0,9,0,92,7,9, -0,93,7,-12,0,5,0,0,0,17,0,7,0,20,1,7,0,94,7,4,0,95,7,4,0,37,0,-11,0,4,0,2, -0,18,0,2,0,20,0,2,0,43,0,2,0,70,0,-10,0,4,0,0,0,17,0,62,0,96,7,7,0,20,1,7, -0,37,0,-9,0,6,0,2,0,97,7,2,0,98,7,2,0,18,0,2,0,99,7,0,0,100,7,0,0,101,7,-8, -0,5,0,4,0,18,0,4,0,37,0,0,0,17,0,0,0,102,7,0,0,103,7,-7,0,3,0,4,0,18,0,4, -0,37,0,0,0,17,0,-6,0,4,0,2,0,104,7,2,0,105,7,2,0,20,0,2,0,37,0,-5,0,6,0,0, -0,17,0,0,0,106,7,2,0,107,7,2,0,-100,2,2,0,13,1,2,0,70,0,-4,0,5,0,0,0,17,0,7, -0,112,0,7,0,-17,3,2,0,20,0,2,0,122,2,-3,0,3,0,0,0,17,0,4,0,110,2,4,0,104,7,-2, -0,7,0,0,0,17,0,7,0,-17,3,0,0,108,7,0,0,109,7,2,0,13,1,2,0,43,0,4,0,110,7,-1, -0,3,0,32,0,111,7,0,0,112,7,0,0,113,7,0,1,18,0,0,1,0,0,0,1,1,0,2,0,18,0,2, -0,90,7,2,0,20,0,2,0,114,7,2,0,115,7,2,0,116,7,2,0,43,0,2,0,70,0,0,0,17,0,9, -0,2,0,1,1,117,7,32,0,45,0,2,0,-47,4,2,0,20,7,2,0,118,7,2,0,37,0,2,1,11,0,0, -0,17,0,0,0,18,0,0,0,119,7,2,0,20,0,2,0,122,2,2,0,120,7,4,0,121,7,4,0,122,7,4, -0,123,7,4,0,124,7,4,0,125,7,3,1,1,0,0,0,126,7,4,1,4,0,42,0,-36,5,0,0,127,7,4, -0,13,1,4,0,20,0,1,1,18,0,1,1,0,0,1,1,1,0,1,1,-128,7,2,0,18,0,2,0,20,0,2, -0,-127,7,2,0,116,7,2,0,90,7,2,0,-126,7,2,0,70,0,2,0,12,1,0,0,17,0,9,0,2,0,5, -1,117,7,0,1,-125,7,2,0,15,0,2,0,-124,7,4,0,-123,7,6,1,3,0,4,0,-74,2,4,0,37,0,32, -0,45,0,7,1,12,0,-111,0,-122,7,2,0,18,0,2,0,20,0,4,0,58,7,4,0,92,0,0,0,17,0,0, -0,-121,7,2,0,-120,7,2,0,-119,7,2,0,-118,7,2,0,-117,7,7,0,-116,7,8,1,10,0,2,0,20,0,2, -0,-115,7,4,0,58,7,4,0,92,0,2,0,-114,7,-28,0,18,7,2,0,18,0,2,0,-113,7,2,0,-112,7,2, -0,-111,7,9,1,7,0,2,0,20,0,2,0,-115,7,4,0,58,7,4,0,92,0,2,0,18,0,2,0,-110,7,7, -0,109,3,10,1,11,0,4,0,-74,2,2,0,18,0,2,0,20,0,32,0,45,0,74,0,-109,7,0,0,17,0,7, -0,-108,7,7,0,-107,7,7,0,21,3,2,0,-106,7,2,0,-105,7,11,1,5,0,2,0,18,0,2,0,20,0,4, -0,37,0,-79,0,-89,6,32,0,39,5,12,1,5,0,4,0,20,0,4,0,18,0,0,0,17,0,0,0,102,7,32, -0,45,0,13,1,13,0,2,0,20,0,2,0,18,0,2,0,90,7,2,0,22,3,7,0,-104,7,7,0,-103,7,7, -0,7,1,7,0,8,1,7,0,-3,2,7,0,0,3,7,0,-102,7,7,0,-101,7,32,0,-100,7,14,1,10,0,2, -0,20,0,2,0,18,0,4,0,58,7,4,0,92,0,0,0,17,0,0,0,-121,7,2,0,43,0,2,0,64,0,2, -0,-99,7,2,0,-98,7,15,1,8,0,32,0,45,0,7,0,-103,2,7,0,-97,7,7,0,-96,7,7,0,-108,2,2, -0,20,0,2,0,122,2,7,0,-95,7,16,1,12,0,2,0,18,0,2,0,13,1,2,0,20,0,2,0,-100,2,2, -0,-74,2,2,0,-94,7,4,0,37,0,7,0,-93,7,7,0,-92,7,7,0,-91,7,7,0,-90,7,0,0,-89,7,17, -1,10,0,2,0,20,0,2,0,18,0,4,0,58,7,4,0,92,0,0,0,17,0,2,0,68,2,2,0,64,0,2, -0,-99,7,2,0,-98,7,63,0,-95,1,18,1,7,0,4,0,110,2,4,0,-88,7,4,0,-87,7,4,0,-86,7,7, -0,-85,7,7,0,-84,7,0,0,108,7,19,1,7,0,0,0,-83,7,32,0,-82,7,0,0,112,7,2,0,-81,7,2, -0,43,0,4,0,70,0,0,0,113,7,20,1,6,0,2,0,20,0,2,0,18,0,4,0,58,7,4,0,92,0,0, -0,-80,7,0,0,-79,7,21,1,1,0,4,0,20,0,22,1,6,0,0,0,95,0,2,0,18,0,2,0,20,0,4, -0,-78,7,7,0,-77,7,42,0,-36,5,23,1,4,0,0,0,-74,0,2,0,20,0,4,0,18,0,32,0,45,0,24, -1,2,0,4,0,18,0,4,0,-121,5,5,1,10,0,5,1,0,0,5,1,1,0,5,1,-128,7,2,0,18,0,2, -0,20,0,2,0,90,7,2,0,-76,7,0,0,17,0,9,0,2,0,32,0,45,0,25,1,10,0,7,0,21,3,7, -0,-75,7,7,0,-74,7,7,0,-73,7,7,0,-72,7,4,0,20,0,7,0,-94,7,7,0,-71,7,7,0,-70,7,7, -0,37,0,-28,0,20,0,27,0,31,0,0,0,-63,0,26,1,-69,7,9,0,-68,7,43,0,-104,0,43,0,-67,7,9, -0,-66,7,36,0,79,0,7,0,109,3,7,0,-65,7,7,0,-64,7,7,0,-63,7,7,0,-62,7,7,0,-61,7,7, -0,-60,7,4,0,93,0,4,0,-59,7,0,0,-58,7,0,0,-57,7,0,0,-56,7,27,1,6,0,27,0,31,0,7, -0,-55,7,7,0,-54,7,7,0,-53,7,2,0,-52,7,2,0,-51,7,28,1,14,0,-75,0,0,0,-75,0,1,0,4, -0,75,5,7,0,76,5,-74,0,77,5,-69,0,-108,5,-28,0,18,7,2,0,13,1,2,0,-115,7,2,0,8,2,2, -0,9,2,2,0,20,0,2,0,-98,5,4,0,70,0,29,1,6,0,29,1,0,0,29,1,1,0,32,0,45,0,9, -0,-50,7,4,0,-38,0,4,0,37,0,63,0,4,0,27,0,31,0,12,0,-49,7,4,0,-121,0,7,0,-48,7,30, -1,25,0,30,1,0,0,30,1,1,0,30,1,38,0,12,0,-47,7,0,0,17,0,7,0,-46,7,7,0,-45,7,7, -0,-44,7,7,0,-43,7,4,0,20,0,7,0,-42,7,7,0,-41,7,7,0,-40,7,7,0,20,1,7,0,-39,1,7, -0,-39,7,7,0,108,2,7,0,-38,7,7,0,-37,7,7,0,-36,7,7,0,-35,7,7,0,-34,7,7,0,-81,0,2, -0,-121,0,2,0,-31,4,31,1,19,0,27,0,31,0,12,0,-33,7,12,0,-32,7,4,0,20,0,4,0,30,4,2, -0,-96,2,2,0,-31,7,2,0,-121,0,2,0,-30,7,2,0,-29,7,2,0,-28,7,2,0,-27,7,2,0,-26,7,4, -0,-25,7,4,0,-24,7,4,0,-23,7,4,0,-22,7,4,0,-21,7,4,0,-20,7,32,1,34,0,32,1,0,0,32, -1,1,0,12,0,49,3,0,0,17,0,2,0,20,0,2,0,-19,7,2,0,-18,7,2,0,-17,7,2,0,10,3,2, -0,-16,7,4,0,-7,1,4,0,-23,7,4,0,-22,7,30,1,-15,7,32,1,38,0,32,1,-14,7,12,0,-13,7,9, -0,-12,7,9,0,-11,7,9,0,-10,7,7,0,7,1,7,0,-81,0,7,0,-57,1,7,0,-9,7,7,0,-8,7,7, -0,2,3,7,0,-7,7,7,0,-6,7,7,0,-5,7,7,0,-4,7,7,0,-3,7,7,0,-2,7,7,0,-10,1,32, -0,-1,7,-110,0,9,0,12,0,0,8,2,0,20,0,2,0,1,8,7,0,20,3,7,0,2,8,7,0,3,8,12, -0,4,8,4,0,5,8,4,0,37,0,33,1,7,0,33,1,0,0,33,1,1,0,12,0,-58,7,4,0,20,0,4, -0,6,8,0,0,17,0,-47,0,7,8,34,1,8,0,34,1,0,0,34,1,1,0,33,1,8,8,36,0,79,0,12, -0,-6,2,4,0,20,0,0,0,17,0,4,0,9,8,-111,0,6,0,27,0,31,0,12,0,0,8,12,0,10,8,12, -0,103,0,4,0,11,8,4,0,37,0,35,1,16,0,-75,0,0,0,-75,0,1,0,4,0,75,5,7,0,76,5,-74, -0,77,5,2,0,78,5,-69,0,-108,5,-111,0,-9,2,0,0,13,1,0,0,-37,5,2,0,20,0,2,0,12,8,2, -0,-101,5,2,0,-98,5,2,0,13,8,7,0,14,8,36,1,5,0,36,1,0,0,36,1,1,0,36,0,79,0,2, -0,20,0,0,0,15,8,37,1,12,0,37,1,0,0,37,1,1,0,9,0,2,0,2,0,18,0,2,0,20,0,0, -0,16,8,0,0,17,8,0,0,15,8,7,0,18,8,7,0,19,8,4,0,37,0,36,0,79,0,38,1,9,0,38, -1,0,0,38,1,1,0,32,0,20,8,0,0,21,8,7,0,22,8,2,0,23,8,2,0,20,0,2,0,18,0,2, -0,37,0,39,1,7,0,42,0,-36,5,26,0,24,8,4,0,20,0,4,0,25,8,12,0,26,8,32,0,20,8,0, -0,21,8,40,1,12,0,32,0,20,8,2,0,27,8,2,0,20,0,2,0,28,8,2,0,29,8,0,0,21,8,32, -0,30,8,0,0,31,8,7,0,32,8,7,0,-39,1,7,0,33,8,7,0,34,8,41,1,6,0,32,0,20,8,4, -0,9,8,4,0,35,8,4,0,93,0,4,0,37,0,0,0,21,8,42,1,4,0,32,0,20,8,4,0,20,0,4, -0,9,8,0,0,21,8,43,1,4,0,32,0,20,8,4,0,20,0,4,0,9,8,0,0,21,8,44,1,10,0,32, -0,20,8,4,0,36,8,7,0,-127,0,4,0,20,0,2,0,-42,5,2,0,37,8,2,0,43,0,2,0,70,0,7, -0,38,8,0,0,21,8,45,1,4,0,32,0,20,8,4,0,20,0,4,0,9,8,0,0,21,8,46,1,10,0,32, -0,20,8,2,0,18,0,2,0,-95,3,4,0,91,0,4,0,92,0,7,0,-97,7,7,0,-96,7,4,0,37,0,-111, -0,-122,7,0,0,21,8,47,1,4,0,32,0,20,8,4,0,7,3,4,0,39,8,0,0,21,8,48,1,5,0,32, -0,20,8,7,0,-127,0,4,0,40,8,4,0,7,3,4,0,8,3,49,1,6,0,32,0,20,8,4,0,41,8,4, -0,42,8,7,0,43,8,7,0,44,8,0,0,21,8,50,1,16,0,32,0,20,8,32,0,-14,7,4,0,18,0,7, -0,45,8,7,0,46,8,7,0,47,8,7,0,48,8,7,0,49,8,7,0,50,8,7,0,51,8,7,0,52,8,7, -0,53,8,2,0,20,0,2,0,37,0,2,0,43,0,2,0,70,0,51,1,3,0,32,0,20,8,4,0,20,0,4, -0,123,5,52,1,5,0,32,0,20,8,4,0,20,0,4,0,37,0,7,0,54,8,0,0,21,8,53,1,10,0,32, -0,20,8,0,0,21,8,2,0,55,8,2,0,56,8,0,0,57,8,0,0,58,8,7,0,59,8,7,0,60,8,7, -0,61,8,7,0,62,8,54,1,8,0,7,0,9,0,7,0,10,0,7,0,11,0,7,0,12,0,7,0,63,8,7, -0,64,8,2,0,20,0,2,0,123,5,55,1,8,0,7,0,9,0,7,0,10,0,7,0,11,0,7,0,12,0,7, -0,63,8,7,0,64,8,2,0,20,0,2,0,123,5,56,1,8,0,7,0,9,0,7,0,10,0,7,0,11,0,7, -0,12,0,7,0,63,8,7,0,64,8,2,0,20,0,2,0,123,5,57,1,7,0,32,0,20,8,0,0,21,8,7, -0,20,1,7,0,30,1,2,0,20,0,2,0,13,1,4,0,37,0,58,1,5,0,32,0,-45,2,7,0,20,1,2, -0,-41,2,0,0,-39,2,0,0,65,8,59,1,10,0,59,1,0,0,59,1,1,0,2,0,18,0,2,0,20,0,0, -0,66,8,7,0,-36,0,7,0,-35,0,2,0,-58,7,2,0,67,8,32,0,45,0,60,1,22,0,60,1,0,0,60, -1,1,0,2,0,20,0,2,0,13,1,2,0,68,8,2,0,69,8,36,0,79,0,-111,0,-122,7,32,0,-89,0,7, -0,91,0,7,0,92,0,7,0,70,8,7,0,71,8,7,0,72,8,7,0,73,8,7,0,-107,2,7,0,-67,1,7, -0,-120,7,7,0,74,8,0,0,75,8,0,0,76,8,12,0,-4,2,61,1,8,0,7,0,-31,1,7,0,-97,7,7, -0,-96,7,9,0,2,0,2,0,77,8,2,0,78,8,2,0,79,8,2,0,80,8,62,1,18,0,62,1,0,0,62, -1,1,0,62,1,81,8,0,0,17,0,61,1,82,8,2,0,18,0,2,0,20,0,2,0,83,8,2,0,84,8,2, -0,85,8,2,0,86,8,4,0,43,0,7,0,87,8,7,0,88,8,4,0,89,8,4,0,90,8,62,1,91,8,63, -1,92,8,64,1,32,0,64,1,0,0,64,1,1,0,64,1,93,8,0,0,17,0,0,0,94,8,2,0,18,0,2, -0,20,0,2,0,-14,6,2,0,20,7,2,0,95,8,2,0,-119,0,2,0,84,8,2,0,-25,6,12,0,-127,7,12, -0,96,8,27,0,-9,5,9,0,97,8,7,0,87,8,7,0,88,8,7,0,-5,1,7,0,98,8,2,0,99,8,2, -0,100,8,7,0,101,8,7,0,102,8,2,0,103,8,2,0,104,8,24,0,105,8,24,0,106,8,24,0,107,8,65, -1,-103,0,66,1,108,8,63,1,6,0,63,1,0,0,63,1,1,0,64,1,109,8,64,1,110,8,62,1,111,8,62, -1,91,8,57,0,16,0,27,0,31,0,12,0,112,8,12,0,113,8,61,1,114,8,12,0,115,8,4,0,18,0,4, -0,116,8,4,0,117,8,4,0,118,8,12,0,119,8,66,1,120,8,62,1,121,8,62,1,122,8,9,0,123,8,9, -0,124,8,4,0,125,8,67,1,6,0,4,0,-128,0,4,0,-126,0,4,0,-25,6,0,0,126,8,0,0,127,8,2, -0,37,0,68,1,16,0,2,0,-86,6,2,0,-85,6,2,0,-128,8,2,0,-74,7,2,0,-127,8,2,0,68,0,7, -0,-108,2,7,0,-126,8,7,0,-125,8,2,0,34,1,0,0,-124,8,0,0,42,4,2,0,-123,8,2,0,37,0,4, -0,-122,8,4,0,-121,8,69,1,9,0,7,0,-120,8,7,0,-119,8,7,0,-60,7,7,0,112,0,7,0,-118,8,7, -0,71,5,2,0,-117,8,0,0,-116,8,0,0,37,0,70,1,4,0,7,0,-115,8,7,0,-114,8,2,0,-117,8,2, -0,37,0,71,1,3,0,7,0,-113,8,7,0,-112,8,7,0,15,0,72,1,7,0,0,0,-68,1,2,0,109,4,2, -0,110,4,2,0,111,4,2,0,62,4,4,0,-126,0,4,0,-97,3,73,1,7,0,7,0,-111,8,7,0,-110,8,7, -0,-109,8,7,0,4,2,7,0,-108,8,7,0,-107,8,7,0,-106,8,74,1,4,0,2,0,-105,8,2,0,-104,8,2, -0,-103,8,2,0,-102,8,75,1,2,0,7,0,5,0,7,0,6,0,76,1,2,0,0,0,-87,0,0,0,-101,8,77, -1,1,0,0,0,17,0,78,1,10,0,0,0,-100,8,0,0,-99,8,0,0,-98,8,0,0,-97,8,2,0,-128,8,2, -0,-96,8,7,0,-95,8,7,0,-94,8,7,0,-93,8,7,0,-67,1,79,1,2,0,9,0,-92,8,9,0,-91,8,80, -1,11,0,0,0,111,4,0,0,18,0,0,0,-117,8,0,0,112,0,0,0,-90,8,0,0,109,0,0,0,-74,0,7, -0,-89,8,7,0,-88,8,7,0,-87,8,7,0,-86,8,81,1,8,0,7,0,97,7,7,0,-127,0,7,0,42,4,7, -0,72,2,7,0,-85,8,7,0,-49,0,7,0,-84,8,4,0,18,0,82,1,4,0,2,0,-83,8,2,0,-82,8,2, -0,-81,8,2,0,37,0,83,1,1,0,0,0,17,0,84,1,4,0,7,0,5,0,7,0,6,0,2,0,20,0,2, -0,-80,8,85,1,10,0,2,0,-120,3,2,0,20,0,7,0,-17,3,7,0,-79,8,7,0,-78,8,7,0,-77,8,7, -0,-76,8,84,1,-75,8,84,1,-74,8,84,1,-73,8,60,0,9,0,4,0,20,0,4,0,64,0,24,0,-72,8,24, -0,-71,8,85,1,-70,8,7,0,-69,8,7,0,-68,8,7,0,-67,8,7,0,-66,8,86,1,4,0,46,0,-114,2,7, -0,-65,8,7,0,92,1,7,0,37,0,-87,0,13,0,27,0,31,0,2,0,20,0,2,0,72,5,4,0,109,0,7, -0,-64,8,7,0,1,2,7,0,-63,8,7,0,-62,8,7,0,92,1,2,0,47,1,2,0,37,0,50,0,77,1,86, -1,-61,8,87,1,10,0,4,0,18,0,4,0,-127,0,4,0,20,0,4,0,70,3,4,0,-60,8,4,0,-59,8,4, -0,-58,8,0,0,95,0,0,0,17,0,9,0,2,0,84,0,6,0,87,1,-57,8,4,0,-56,8,4,0,-55,8,4, -0,-54,8,4,0,37,0,9,0,-53,8,88,1,5,0,7,0,66,2,7,0,-74,2,7,0,-39,1,2,0,-52,8,2, -0,37,0,89,1,5,0,7,0,66,2,7,0,-51,8,7,0,-50,8,7,0,-49,8,7,0,-74,2,90,1,7,0,4, -0,-48,8,4,0,-47,8,4,0,-46,8,7,0,-45,8,7,0,-44,8,7,0,-43,8,7,0,-42,8,91,1,26,0,32, -0,-41,8,89,1,66,3,89,1,-40,8,88,1,-39,8,89,1,83,7,7,0,-38,8,7,0,-37,8,7,0,-36,8,7, -0,-35,8,7,0,-44,8,7,0,-43,8,7,0,-74,2,7,0,-97,2,7,0,-34,8,7,0,-33,8,7,0,109,0,7, -0,-32,8,4,0,-48,8,4,0,-31,8,4,0,37,0,4,0,81,0,4,0,-30,8,2,0,20,0,2,0,-29,8,2, -0,-28,8,2,0,100,3,92,1,112,0,27,0,31,0,4,0,20,0,2,0,18,0,2,0,55,8,2,0,-27,8,2, -0,-26,8,2,0,-25,8,2,0,-24,8,2,0,-23,8,2,0,-22,8,2,0,-21,8,2,0,-20,8,2,0,-19,8,2, -0,-18,8,2,0,-17,8,2,0,-16,8,2,0,-15,8,2,0,-14,8,2,0,-13,8,2,0,-47,1,2,0,76,7,2, -0,51,7,2,0,-12,8,2,0,-11,8,2,0,98,3,2,0,99,3,2,0,-10,8,2,0,-9,8,2,0,-8,8,2, -0,-7,8,2,0,-6,8,2,0,-5,8,7,0,-4,8,7,0,-3,8,7,0,-2,8,2,0,-1,8,2,0,0,9,7, -0,1,9,7,0,2,9,7,0,3,9,7,0,58,7,7,0,92,0,7,0,-97,2,7,0,64,7,7,0,4,9,7, -0,5,9,7,0,6,9,7,0,7,9,7,0,57,0,4,0,59,7,4,0,57,7,4,0,8,9,7,0,60,7,7, -0,61,7,7,0,62,7,7,0,9,9,7,0,10,9,7,0,11,9,7,0,12,9,7,0,13,9,7,0,14,9,7, -0,15,9,7,0,16,9,7,0,21,3,7,0,109,0,7,0,17,9,7,0,18,9,7,0,19,9,7,0,20,9,7, -0,21,9,7,0,22,9,7,0,108,2,7,0,23,9,7,0,24,9,4,0,25,9,4,0,26,9,7,0,27,9,7, -0,28,9,7,0,29,9,7,0,30,9,7,0,31,9,7,0,32,9,7,0,33,9,7,0,34,9,7,0,94,3,7, -0,92,3,7,0,93,3,7,0,35,9,7,0,36,9,7,0,37,9,7,0,38,9,7,0,39,9,7,0,40,9,7, -0,41,9,7,0,42,9,7,0,43,9,7,0,28,3,7,0,44,9,7,0,45,9,7,0,46,9,7,0,47,9,7, -0,48,9,7,0,49,9,7,0,50,9,0,0,51,9,63,0,55,3,63,0,52,9,32,0,53,9,32,0,54,9,36, -0,79,0,-108,0,53,3,-108,0,55,9,-120,0,37,0,-120,0,0,0,-120,0,1,0,92,1,56,9,91,1,-121,3,90, -1,-14,7,93,1,57,9,94,1,58,9,94,1,59,9,12,0,60,9,12,0,61,9,-107,0,54,3,32,0,62,9,32, -0,63,9,32,0,64,9,12,0,65,9,12,0,66,9,7,0,-45,0,7,0,83,4,4,0,110,2,4,0,20,0,4, -0,59,7,4,0,67,9,4,0,68,9,4,0,69,9,4,0,57,0,2,0,-38,0,2,0,70,9,2,0,71,9,2, -0,72,9,2,0,47,3,2,0,73,9,0,0,74,9,2,0,75,9,2,0,76,9,2,0,77,9,9,0,78,9,125, -0,-76,3,123,0,34,0,95,1,79,9,7,0,-106,3,7,0,80,9,7,0,81,9,7,0,-14,3,7,0,82,9,7, -0,31,3,7,0,21,3,7,0,83,9,7,0,3,2,7,0,84,9,7,0,85,9,7,0,86,9,7,0,87,9,7, -0,88,9,7,0,89,9,7,0,-105,3,7,0,90,9,7,0,91,9,7,0,92,9,7,0,-104,3,7,0,-108,3,7, -0,-107,3,4,0,93,9,4,0,93,0,4,0,94,9,4,0,95,9,2,0,96,9,2,0,97,9,2,0,98,9,2, -0,99,9,2,0,100,9,2,0,37,0,4,0,70,0,124,0,8,0,95,1,101,9,7,0,102,9,7,0,103,9,7, -0,-94,1,7,0,104,9,4,0,93,0,2,0,105,9,2,0,106,9,96,1,4,0,7,0,5,0,7,0,6,0,7, -0,7,0,7,0,107,9,97,1,6,0,97,1,0,0,97,1,1,0,96,1,108,9,4,0,109,9,2,0,110,9,2, -0,20,0,98,1,5,0,98,1,0,0,98,1,1,0,12,0,111,9,4,0,112,9,4,0,20,0,99,1,9,0,99, -1,0,0,99,1,1,0,12,0,-128,0,98,1,113,9,4,0,20,0,2,0,110,9,2,0,114,9,7,0,94,0,0, -0,115,9,-70,0,5,0,12,0,125,4,4,0,20,0,2,0,116,9,2,0,117,9,9,0,118,9,69,78,68,66,0, -0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 -}; -int DNAlen64= sizeof(DNAstr64); diff --git a/extern/bullet/src/Extras/Serialize/BlenderSerialize/dna249.cpp b/extern/bullet/src/Extras/Serialize/BlenderSerialize/dna249.cpp deleted file mode 100644 index 97881b4f7a1b..000000000000 --- a/extern/bullet/src/Extras/Serialize/BlenderSerialize/dna249.cpp +++ /dev/null @@ -1,1411 +0,0 @@ -/* -bParse -Copyright (c) 2006-2009 Charlie C & Erwin Coumans http://gamekit.googlecode.com - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ -unsigned char DNAstr[]= { -83,68,78,65,78,65,77,69,119,9,0,0,42,110,101,120,116,0,42,112,114,101,118,0,42,100,97,116,97,0,42,102,105, -114,115,116,0,42,108,97,115,116,0,120,0,121,0,122,0,119,0,120,109,105,110,0,120,109,97,120,0,121,109,105,110, -0,121,109,97,120,0,42,112,111,105,110,116,101,114,0,103,114,111,117,112,0,118,97,108,0,118,97,108,50,0,110,97, -109,101,91,51,50,93,0,116,121,112,101,0,115,117,98,116,121,112,101,0,102,108,97,103,0,115,97,118,101,100,0,100, -97,116,97,0,108,101,110,0,116,111,116,97,108,108,101,110,0,42,110,101,119,105,100,0,42,108,105,98,0,110,97,109, -101,91,50,52,93,0,117,115,0,105,99,111,110,95,105,100,0,42,112,114,111,112,101,114,116,105,101,115,0,105,100,0, -42,105,100,98,108,111,99,107,0,42,102,105,108,101,100,97,116,97,0,110,97,109,101,91,50,52,48,93,0,102,105,108, -101,110,97,109,101,91,50,52,48,93,0,116,111,116,0,112,97,100,0,42,112,97,114,101,110,116,0,119,91,50,93,0, -104,91,50,93,0,99,104,97,110,103,101,100,91,50,93,0,112,97,100,48,0,112,97,100,49,0,42,114,101,99,116,91, -50,93,0,42,111,98,0,98,108,111,99,107,116,121,112,101,0,97,100,114,99,111,100,101,0,110,97,109,101,91,49,50, -56,93,0,42,98,112,0,42,98,101,122,116,0,109,97,120,114,99,116,0,116,111,116,114,99,116,0,118,97,114,116,121, -112,101,0,116,111,116,118,101,114,116,0,105,112,111,0,101,120,116,114,97,112,0,114,116,0,98,105,116,109,97,115,107, -0,115,108,105,100,101,95,109,105,110,0,115,108,105,100,101,95,109,97,120,0,99,117,114,118,97,108,0,42,100,114,105, -118,101,114,0,99,117,114,118,101,0,99,117,114,0,115,104,111,119,107,101,121,0,109,117,116,101,105,112,111,0,112,111, -115,0,114,101,108,97,116,105,118,101,0,116,111,116,101,108,101,109,0,112,97,100,50,0,42,119,101,105,103,104,116,115, -0,118,103,114,111,117,112,91,51,50,93,0,115,108,105,100,101,114,109,105,110,0,115,108,105,100,101,114,109,97,120,0, -42,114,101,102,107,101,121,0,101,108,101,109,115,116,114,91,51,50,93,0,101,108,101,109,115,105,122,101,0,98,108,111, -99,107,0,42,105,112,111,0,42,102,114,111,109,0,116,111,116,107,101,121,0,115,108,117,114,112,104,0,42,42,115,99, -114,105,112,116,115,0,42,102,108,97,103,0,97,99,116,115,99,114,105,112,116,0,116,111,116,115,99,114,105,112,116,0, -42,108,105,110,101,0,42,102,111,114,109,97,116,0,98,108,101,110,0,108,105,110,101,110,111,0,115,116,97,114,116,0, -101,110,100,0,102,108,97,103,115,0,99,111,108,111,114,91,52,93,0,112,97,100,91,52,93,0,42,110,97,109,101,0, -110,108,105,110,101,115,0,108,105,110,101,115,0,42,99,117,114,108,0,42,115,101,108,108,0,99,117,114,99,0,115,101, -108,99,0,109,97,114,107,101,114,115,0,42,117,110,100,111,95,98,117,102,0,117,110,100,111,95,112,111,115,0,117,110, -100,111,95,108,101,110,0,42,99,111,109,112,105,108,101,100,0,109,116,105,109,101,0,115,105,122,101,0,115,101,101,107, -0,112,97,115,115,101,112,97,114,116,97,108,112,104,97,0,97,110,103,108,101,0,99,108,105,112,115,116,97,0,99,108, -105,112,101,110,100,0,108,101,110,115,0,111,114,116,104,111,95,115,99,97,108,101,0,100,114,97,119,115,105,122,101,0, -115,104,105,102,116,120,0,115,104,105,102,116,121,0,89,70,95,100,111,102,100,105,115,116,0,89,70,95,97,112,101,114, -116,117,114,101,0,89,70,95,98,107,104,116,121,112,101,0,89,70,95,98,107,104,98,105,97,115,0,89,70,95,98,107, -104,114,111,116,0,115,99,114,105,112,116,108,105,110,107,0,42,100,111,102,95,111,98,0,102,114,97,109,101,110,114,0, -102,114,97,109,101,115,0,111,102,102,115,101,116,0,115,102,114,97,0,102,105,101,95,105,109,97,0,99,121,99,108,0, -111,107,0,109,117,108,116,105,95,105,110,100,101,120,0,108,97,121,101,114,0,112,97,115,115,0,109,101,110,117,110,114, -0,105,98,117,102,115,0,42,103,112,117,116,101,120,116,117,114,101,0,42,97,110,105,109,0,42,114,114,0,115,111,117, -114,99,101,0,108,97,115,116,102,114,97,109,101,0,116,112,97,103,101,102,108,97,103,0,116,111,116,98,105,110,100,0, -120,114,101,112,0,121,114,101,112,0,116,119,115,116,97,0,116,119,101,110,100,0,98,105,110,100,99,111,100,101,0,42, -114,101,112,98,105,110,100,0,42,112,97,99,107,101,100,102,105,108,101,0,42,112,114,101,118,105,101,119,0,108,97,115, -116,117,112,100,97,116,101,0,108,97,115,116,117,115,101,100,0,97,110,105,109,115,112,101,101,100,0,103,101,110,95,120, -0,103,101,110,95,121,0,103,101,110,95,116,121,112,101,0,97,115,112,120,0,97,115,112,121,0,42,118,110,111,100,101, -0,116,101,120,99,111,0,109,97,112,116,111,0,109,97,112,116,111,110,101,103,0,98,108,101,110,100,116,121,112,101,0, -42,111,98,106,101,99,116,0,42,116,101,120,0,117,118,110,97,109,101,91,51,50,93,0,112,114,111,106,120,0,112,114, -111,106,121,0,112,114,111,106,122,0,109,97,112,112,105,110,103,0,111,102,115,91,51,93,0,115,105,122,101,91,51,93, -0,116,101,120,102,108,97,103,0,99,111,108,111,114,109,111,100,101,108,0,112,109,97,112,116,111,0,112,109,97,112,116, -111,110,101,103,0,110,111,114,109,97,112,115,112,97,99,101,0,119,104,105,99,104,95,111,117,116,112,117,116,0,112,97, -100,91,50,93,0,114,0,103,0,98,0,107,0,100,101,102,95,118,97,114,0,99,111,108,102,97,99,0,110,111,114,102, -97,99,0,118,97,114,102,97,99,0,100,105,115,112,102,97,99,0,119,97,114,112,102,97,99,0,110,97,109,101,91,49, -54,48,93,0,42,104,97,110,100,108,101,0,42,112,110,97,109,101,0,42,115,116,110,97,109,101,115,0,115,116,121,112, -101,115,0,118,97,114,115,0,42,118,97,114,115,116,114,0,42,114,101,115,117,108,116,0,42,99,102,114,97,0,100,97, -116,97,91,51,50,93,0,40,42,100,111,105,116,41,40,41,0,40,42,105,110,115,116,97,110,99,101,95,105,110,105,116, -41,40,41,0,40,42,99,97,108,108,98,97,99,107,41,40,41,0,118,101,114,115,105,111,110,0,97,0,105,112,111,116, -121,112,101,0,42,105,109,97,0,42,99,117,98,101,91,54,93,0,105,109,97,116,91,52,93,91,52,93,0,111,98,105, -109,97,116,91,51,93,91,51,93,0,115,116,121,112,101,0,118,105,101,119,115,99,97,108,101,0,110,111,116,108,97,121, -0,99,117,98,101,114,101,115,0,100,101,112,116,104,0,114,101,99,97,108,99,0,108,97,115,116,115,105,122,101,0,110, -111,105,115,101,115,105,122,101,0,116,117,114,98,117,108,0,98,114,105,103,104,116,0,99,111,110,116,114,97,115,116,0, -114,102,97,99,0,103,102,97,99,0,98,102,97,99,0,102,105,108,116,101,114,115,105,122,101,0,109,103,95,72,0,109, -103,95,108,97,99,117,110,97,114,105,116,121,0,109,103,95,111,99,116,97,118,101,115,0,109,103,95,111,102,102,115,101, -116,0,109,103,95,103,97,105,110,0,100,105,115,116,95,97,109,111,117,110,116,0,110,115,95,111,117,116,115,99,97,108, -101,0,118,110,95,119,49,0,118,110,95,119,50,0,118,110,95,119,51,0,118,110,95,119,52,0,118,110,95,109,101,120, -112,0,118,110,95,100,105,115,116,109,0,118,110,95,99,111,108,116,121,112,101,0,110,111,105,115,101,100,101,112,116,104, -0,110,111,105,115,101,116,121,112,101,0,110,111,105,115,101,98,97,115,105,115,0,110,111,105,115,101,98,97,115,105,115, -50,0,105,109,97,102,108,97,103,0,99,114,111,112,120,109,105,110,0,99,114,111,112,121,109,105,110,0,99,114,111,112, -120,109,97,120,0,99,114,111,112,121,109,97,120,0,120,114,101,112,101,97,116,0,121,114,101,112,101,97,116,0,101,120, -116,101,110,100,0,99,104,101,99,107,101,114,100,105,115,116,0,110,97,98,108,97,0,105,117,115,101,114,0,42,110,111, -100,101,116,114,101,101,0,42,112,108,117,103,105,110,0,42,99,111,98,97,0,42,101,110,118,0,117,115,101,95,110,111, -100,101,115,0,112,97,100,91,55,93,0,108,111,99,91,51,93,0,114,111,116,91,51,93,0,109,97,116,91,52,93,91, -52,93,0,109,105,110,91,51,93,0,109,97,120,91,51,93,0,112,97,100,51,0,109,111,100,101,0,116,111,116,101,120, -0,115,104,100,119,114,0,115,104,100,119,103,0,115,104,100,119,98,0,115,104,100,119,112,97,100,0,101,110,101,114,103, -121,0,100,105,115,116,0,115,112,111,116,115,105,122,101,0,115,112,111,116,98,108,101,110,100,0,104,97,105,110,116,0, -97,116,116,49,0,97,116,116,50,0,42,99,117,114,102,97,108,108,111,102,102,0,102,97,108,108,111,102,102,95,116,121, -112,101,0,115,104,97,100,115,112,111,116,115,105,122,101,0,98,105,97,115,0,115,111,102,116,0,98,117,102,115,105,122, -101,0,115,97,109,112,0,98,117,102,102,101,114,115,0,102,105,108,116,101,114,116,121,112,101,0,98,117,102,102,108,97, -103,0,98,117,102,116,121,112,101,0,114,97,121,95,115,97,109,112,0,114,97,121,95,115,97,109,112,121,0,114,97,121, -95,115,97,109,112,122,0,114,97,121,95,115,97,109,112,95,116,121,112,101,0,97,114,101,97,95,115,104,97,112,101,0, -97,114,101,97,95,115,105,122,101,0,97,114,101,97,95,115,105,122,101,121,0,97,114,101,97,95,115,105,122,101,122,0, -97,100,97,112,116,95,116,104,114,101,115,104,0,114,97,121,95,115,97,109,112,95,109,101,116,104,111,100,0,116,101,120, -97,99,116,0,115,104,97,100,104,97,108,111,115,116,101,112,0,115,117,110,95,101,102,102,101,99,116,95,116,121,112,101, -0,115,107,121,98,108,101,110,100,116,121,112,101,0,104,111,114,105,122,111,110,95,98,114,105,103,104,116,110,101,115,115, -0,115,112,114,101,97,100,0,115,117,110,95,98,114,105,103,104,116,110,101,115,115,0,115,117,110,95,115,105,122,101,0, -98,97,99,107,115,99,97,116,116,101,114,101,100,95,108,105,103,104,116,0,115,117,110,95,105,110,116,101,110,115,105,116, -121,0,97,116,109,95,116,117,114,98,105,100,105,116,121,0,97,116,109,95,105,110,115,99,97,116,116,101,114,105,110,103, -95,102,97,99,116,111,114,0,97,116,109,95,101,120,116,105,110,99,116,105,111,110,95,102,97,99,116,111,114,0,97,116, -109,95,100,105,115,116,97,110,99,101,95,102,97,99,116,111,114,0,115,107,121,98,108,101,110,100,102,97,99,0,115,107, -121,95,101,120,112,111,115,117,114,101,0,115,107,121,95,99,111,108,111,114,115,112,97,99,101,0,112,97,100,52,0,89, -70,95,110,117,109,112,104,111,116,111,110,115,0,89,70,95,110,117,109,115,101,97,114,99,104,0,89,70,95,112,104,100, -101,112,116,104,0,89,70,95,117,115,101,113,109,99,0,89,70,95,98,117,102,115,105,122,101,0,89,70,95,112,97,100, -0,89,70,95,99,97,117,115,116,105,99,98,108,117,114,0,89,70,95,108,116,114,97,100,105,117,115,0,89,70,95,103, -108,111,119,105,110,116,0,89,70,95,103,108,111,119,111,102,115,0,89,70,95,103,108,111,119,116,121,112,101,0,89,70, -95,112,97,100,50,0,42,109,116,101,120,91,49,56,93,0,115,112,101,99,114,0,115,112,101,99,103,0,115,112,101,99, -98,0,109,105,114,114,0,109,105,114,103,0,109,105,114,98,0,97,109,98,114,0,97,109,98,98,0,97,109,98,103,0, -97,109,98,0,101,109,105,116,0,97,110,103,0,115,112,101,99,116,114,97,0,114,97,121,95,109,105,114,114,111,114,0, -97,108,112,104,97,0,114,101,102,0,115,112,101,99,0,122,111,102,102,115,0,97,100,100,0,116,114,97,110,115,108,117, -99,101,110,99,121,0,102,114,101,115,110,101,108,95,109,105,114,0,102,114,101,115,110,101,108,95,109,105,114,95,105,0, -102,114,101,115,110,101,108,95,116,114,97,0,102,114,101,115,110,101,108,95,116,114,97,95,105,0,102,105,108,116,101,114, -0,116,120,95,108,105,109,105,116,0,116,120,95,102,97,108,108,111,102,102,0,114,97,121,95,100,101,112,116,104,0,114, -97,121,95,100,101,112,116,104,95,116,114,97,0,104,97,114,0,115,101,101,100,49,0,115,101,101,100,50,0,103,108,111, -115,115,95,109,105,114,0,103,108,111,115,115,95,116,114,97,0,115,97,109,112,95,103,108,111,115,115,95,109,105,114,0, -115,97,109,112,95,103,108,111,115,115,95,116,114,97,0,97,100,97,112,116,95,116,104,114,101,115,104,95,109,105,114,0, -97,100,97,112,116,95,116,104,114,101,115,104,95,116,114,97,0,97,110,105,115,111,95,103,108,111,115,115,95,109,105,114, -0,100,105,115,116,95,109,105,114,0,102,97,100,101,116,111,95,109,105,114,0,115,104,97,100,101,95,102,108,97,103,0, -109,111,100,101,95,108,0,102,108,97,114,101,99,0,115,116,97,114,99,0,108,105,110,101,99,0,114,105,110,103,99,0, -104,97,115,105,122,101,0,102,108,97,114,101,115,105,122,101,0,115,117,98,115,105,122,101,0,102,108,97,114,101,98,111, -111,115,116,0,115,116,114,97,110,100,95,115,116,97,0,115,116,114,97,110,100,95,101,110,100,0,115,116,114,97,110,100, -95,101,97,115,101,0,115,116,114,97,110,100,95,115,117,114,102,110,111,114,0,115,116,114,97,110,100,95,109,105,110,0, -115,116,114,97,110,100,95,119,105,100,116,104,102,97,100,101,0,115,116,114,97,110,100,95,117,118,110,97,109,101,91,51, -50,93,0,115,98,105,97,115,0,108,98,105,97,115,0,115,104,97,100,95,97,108,112,104,97,0,115,101,112,116,101,120, -0,114,103,98,115,101,108,0,112,114,95,116,121,112,101,0,112,114,95,98,97,99,107,0,112,114,95,108,97,109,112,0, -109,108,95,102,108,97,103,0,100,105,102,102,95,115,104,97,100,101,114,0,115,112,101,99,95,115,104,97,100,101,114,0, -114,111,117,103,104,110,101,115,115,0,114,101,102,114,97,99,0,112,97,114,97,109,91,52,93,0,114,109,115,0,100,97, -114,107,110,101,115,115,0,42,114,97,109,112,95,99,111,108,0,42,114,97,109,112,95,115,112,101,99,0,114,97,109,112, -105,110,95,99,111,108,0,114,97,109,112,105,110,95,115,112,101,99,0,114,97,109,112,98,108,101,110,100,95,99,111,108, -0,114,97,109,112,98,108,101,110,100,95,115,112,101,99,0,114,97,109,112,95,115,104,111,119,0,114,97,109,112,102,97, -99,95,99,111,108,0,114,97,109,112,102,97,99,95,115,112,101,99,0,42,103,114,111,117,112,0,102,114,105,99,116,105, -111,110,0,102,104,0,114,101,102,108,101,99,116,0,102,104,100,105,115,116,0,120,121,102,114,105,99,116,0,100,121,110, -97,109,111,100,101,0,115,115,115,95,114,97,100,105,117,115,91,51,93,0,115,115,115,95,99,111,108,91,51,93,0,115, -115,115,95,101,114,114,111,114,0,115,115,115,95,115,99,97,108,101,0,115,115,115,95,105,111,114,0,115,115,115,95,99, -111,108,102,97,99,0,115,115,115,95,116,101,120,102,97,99,0,115,115,115,95,102,114,111,110,116,0,115,115,115,95,98, -97,99,107,0,115,115,115,95,102,108,97,103,0,115,115,115,95,112,114,101,115,101,116,0,89,70,95,97,114,0,89,70, -95,97,103,0,89,70,95,97,98,0,89,70,95,100,115,99,97,108,101,0,89,70,95,100,112,119,114,0,89,70,95,100, -115,109,112,0,89,70,95,112,114,101,115,101,116,0,89,70,95,100,106,105,116,0,103,112,117,109,97,116,101,114,105,97, -108,0,110,97,109,101,91,50,53,54,93,0,115,99,97,108,101,0,42,98,98,0,105,49,0,106,49,0,107,49,0,105, -50,0,106,50,0,107,50,0,115,101,108,99,111,108,49,0,115,101,108,99,111,108,50,0,113,117,97,116,91,52,93,0, -101,120,112,120,0,101,120,112,121,0,101,120,112,122,0,114,97,100,0,114,97,100,50,0,115,0,42,109,97,116,0,42, -105,109,97,116,0,101,108,101,109,115,0,100,105,115,112,0,42,42,109,97,116,0,116,111,116,99,111,108,0,119,105,114, -101,115,105,122,101,0,114,101,110,100,101,114,115,105,122,101,0,116,104,114,101,115,104,0,118,101,99,91,51,93,91,51, -93,0,97,108,102,97,0,119,101,105,103,104,116,0,114,97,100,105,117,115,0,104,49,0,104,50,0,102,49,0,102,50, -0,102,51,0,104,105,100,101,0,118,101,99,91,52,93,0,109,97,116,95,110,114,0,112,110,116,115,117,0,112,110,116, -115,118,0,114,101,115,111,108,117,0,114,101,115,111,108,118,0,111,114,100,101,114,117,0,111,114,100,101,114,118,0,102, -108,97,103,117,0,102,108,97,103,118,0,42,107,110,111,116,115,117,0,42,107,110,111,116,115,118,0,116,105,108,116,95, -105,110,116,101,114,112,0,114,97,100,105,117,115,95,105,110,116,101,114,112,0,99,104,97,114,105,100,120,0,107,101,114, -110,0,104,0,110,117,114,98,0,42,98,101,118,111,98,106,0,42,116,97,112,101,114,111,98,106,0,42,116,101,120,116, -111,110,99,117,114,118,101,0,42,112,97,116,104,0,42,107,101,121,0,98,101,118,0,112,97,116,104,108,101,110,0,98, -101,118,114,101,115,111,108,0,119,105,100,116,104,0,101,120,116,49,0,101,120,116,50,0,114,101,115,111,108,117,95,114, -101,110,0,114,101,115,111,108,118,95,114,101,110,0,115,112,97,99,101,109,111,100,101,0,115,112,97,99,105,110,103,0, -108,105,110,101,100,105,115,116,0,115,104,101,97,114,0,102,115,105,122,101,0,119,111,114,100,115,112,97,99,101,0,117, -108,112,111,115,0,117,108,104,101,105,103,104,116,0,120,111,102,0,121,111,102,0,108,105,110,101,119,105,100,116,104,0, -42,115,116,114,0,102,97,109,105,108,121,91,50,52,93,0,42,118,102,111,110,116,0,42,118,102,111,110,116,98,0,42, -118,102,111,110,116,105,0,42,118,102,111,110,116,98,105,0,115,101,112,99,104,97,114,0,116,111,116,98,111,120,0,97, -99,116,98,111,120,0,42,116,98,0,115,101,108,115,116,97,114,116,0,115,101,108,101,110,100,0,42,115,116,114,105,110, -102,111,0,99,117,114,105,110,102,111,0,101,102,102,101,99,116,0,42,109,102,97,99,101,0,42,109,116,102,97,99,101, -0,42,116,102,97,99,101,0,42,109,118,101,114,116,0,42,109,101,100,103,101,0,42,100,118,101,114,116,0,42,109,99, -111,108,0,42,109,115,116,105,99,107,121,0,42,116,101,120,99,111,109,101,115,104,0,42,109,115,101,108,101,99,116,0, -118,100,97,116,97,0,101,100,97,116,97,0,102,100,97,116,97,0,116,111,116,101,100,103,101,0,116,111,116,102,97,99, -101,0,116,111,116,115,101,108,101,99,116,0,97,99,116,95,102,97,99,101,0,99,117,98,101,109,97,112,115,105,122,101, -0,115,109,111,111,116,104,114,101,115,104,0,115,117,98,100,105,118,0,115,117,98,100,105,118,114,0,115,117,98,115,117, -114,102,116,121,112,101,0,42,109,114,0,42,112,118,0,42,116,112,97,103,101,0,117,118,91,52,93,91,50,93,0,99, -111,108,91,52,93,0,116,114,97,110,115,112,0,116,105,108,101,0,117,110,119,114,97,112,0,118,49,0,118,50,0,118, -51,0,118,52,0,101,100,99,111,100,101,0,99,114,101,97,115,101,0,98,119,101,105,103,104,116,0,100,101,102,95,110, -114,0,42,100,119,0,116,111,116,119,101,105,103,104,116,0,99,111,91,51,93,0,110,111,91,51,93,0,112,97,100,91, -51,93,0,117,118,91,50,93,0,99,111,91,50,93,0,105,110,100,101,120,0,102,0,105,0,115,91,50,53,54,93,0, -118,91,52,93,0,109,105,100,0,118,91,50,93,0,42,102,97,99,101,115,0,42,99,111,108,102,97,99,101,115,0,42, -101,100,103,101,115,0,42,101,100,103,101,95,98,111,117,110,100,97,114,121,95,115,116,97,116,101,115,0,42,118,101,114, -116,95,101,100,103,101,95,109,97,112,0,42,118,101,114,116,95,102,97,99,101,95,109,97,112,0,42,109,97,112,95,109, -101,109,0,42,118,101,114,116,115,0,108,101,118,101,108,115,0,108,101,118,101,108,95,99,111,117,110,116,0,99,117,114, -114,101,110,116,0,110,101,119,108,118,108,0,101,100,103,101,108,118,108,0,112,105,110,108,118,108,0,114,101,110,100,101, -114,108,118,108,0,117,115,101,95,99,111,108,0,42,101,100,103,101,95,102,108,97,103,115,0,42,101,100,103,101,95,99, -114,101,97,115,101,115,0,42,118,101,114,116,95,109,97,112,0,42,101,100,103,101,95,109,97,112,0,42,111,108,100,95, -102,97,99,101,115,0,42,111,108,100,95,101,100,103,101,115,0,42,101,114,114,111,114,0,109,111,100,105,102,105,101,114, -0,115,117,98,100,105,118,84,121,112,101,0,114,101,110,100,101,114,76,101,118,101,108,115,0,42,101,109,67,97,99,104, -101,0,42,109,67,97,99,104,101,0,100,101,102,97,120,105,115,0,112,97,100,91,54,93,0,108,101,110,103,116,104,0, -114,97,110,100,111,109,105,122,101,0,115,101,101,100,0,42,111,98,95,97,114,109,0,42,115,116,97,114,116,95,99,97, -112,0,42,101,110,100,95,99,97,112,0,42,99,117,114,118,101,95,111,98,0,42,111,102,102,115,101,116,95,111,98,0, -111,102,102,115,101,116,91,51,93,0,115,99,97,108,101,91,51,93,0,109,101,114,103,101,95,100,105,115,116,0,102,105, -116,95,116,121,112,101,0,111,102,102,115,101,116,95,116,121,112,101,0,99,111,117,110,116,0,97,120,105,115,0,116,111, -108,101,114,97,110,99,101,0,42,109,105,114,114,111,114,95,111,98,0,115,112,108,105,116,95,97,110,103,108,101,0,118, -97,108,117,101,0,114,101,115,0,118,97,108,95,102,108,97,103,115,0,108,105,109,95,102,108,97,103,115,0,101,95,102, -108,97,103,115,0,98,101,118,101,108,95,97,110,103,108,101,0,100,101,102,103,114,112,95,110,97,109,101,91,51,50,93, -0,42,116,101,120,116,117,114,101,0,115,116,114,101,110,103,116,104,0,100,105,114,101,99,116,105,111,110,0,109,105,100, -108,101,118,101,108,0,116,101,120,109,97,112,112,105,110,103,0,42,109,97,112,95,111,98,106,101,99,116,0,117,118,108, -97,121,101,114,95,110,97,109,101,91,51,50,93,0,117,118,108,97,121,101,114,95,116,109,112,0,42,112,114,111,106,101, -99,116,111,114,115,91,49,48,93,0,42,105,109,97,103,101,0,110,117,109,95,112,114,111,106,101,99,116,111,114,115,0, -97,115,112,101,99,116,120,0,97,115,112,101,99,116,121,0,112,101,114,99,101,110,116,0,102,97,99,101,67,111,117,110, -116,0,102,97,99,0,114,101,112,101,97,116,0,42,111,98,106,101,99,116,99,101,110,116,101,114,0,115,116,97,114,116, -120,0,115,116,97,114,116,121,0,104,101,105,103,104,116,0,110,97,114,114,111,119,0,115,112,101,101,100,0,100,97,109, -112,0,102,97,108,108,111,102,102,0,116,105,109,101,111,102,102,115,0,108,105,102,101,116,105,109,101,0,100,101,102,111, -114,109,102,108,97,103,0,109,117,108,116,105,0,42,112,114,101,118,67,111,115,0,112,97,114,101,110,116,105,110,118,91, -52,93,91,52,93,0,99,101,110,116,91,51,93,0,42,105,110,100,101,120,97,114,0,116,111,116,105,110,100,101,120,0, -102,111,114,99,101,0,42,99,108,111,116,104,79,98,106,101,99,116,0,42,115,105,109,95,112,97,114,109,115,0,42,99, -111,108,108,95,112,97,114,109,115,0,42,112,111,105,110,116,95,99,97,99,104,101,0,42,120,0,42,120,110,101,119,0, -42,120,111,108,100,0,42,99,117,114,114,101,110,116,95,120,110,101,119,0,42,99,117,114,114,101,110,116,95,120,0,42, -99,117,114,114,101,110,116,95,118,0,42,109,102,97,99,101,115,0,110,117,109,118,101,114,116,115,0,110,117,109,102,97, -99,101,115,0,97,98,115,111,114,112,116,105,111,110,0,116,105,109,101,0,42,98,118,104,116,114,101,101,0,42,100,109, -0,111,112,101,114,97,116,105,111,110,0,118,101,114,116,101,120,0,116,111,116,105,110,102,108,117,101,110,99,101,0,103, -114,105,100,115,105,122,101,0,110,101,101,100,98,105,110,100,0,42,98,105,110,100,119,101,105,103,104,116,115,0,42,98, -105,110,100,99,111,115,0,116,111,116,99,97,103,101,118,101,114,116,0,42,100,121,110,103,114,105,100,0,42,100,121,110, -105,110,102,108,117,101,110,99,101,115,0,42,100,121,110,118,101,114,116,115,0,42,112,97,100,50,0,100,121,110,103,114, -105,100,115,105,122,101,0,100,121,110,99,101,108,108,109,105,110,91,51,93,0,100,121,110,99,101,108,108,119,105,100,116, -104,0,98,105,110,100,109,97,116,91,52,93,91,52,93,0,42,112,115,121,115,0,116,111,116,100,109,118,101,114,116,0, -116,111,116,100,109,101,100,103,101,0,116,111,116,100,109,102,97,99,101,0,112,115,121,115,0,114,116,91,50,93,0,42, -102,97,99,101,112,97,0,118,103,114,111,117,112,0,112,114,111,116,101,99,116,0,42,102,115,115,0,42,116,97,114,103, -101,116,0,42,97,117,120,84,97,114,103,101,116,0,118,103,114,111,117,112,95,110,97,109,101,91,51,50,93,0,107,101, -101,112,68,105,115,116,0,115,104,114,105,110,107,84,121,112,101,0,115,104,114,105,110,107,79,112,116,115,0,112,114,111, -106,65,120,105,115,0,115,117,98,115,117,114,102,76,101,118,101,108,115,0,42,111,114,105,103,105,110,0,102,97,99,116, -111,114,0,108,105,109,105,116,91,50,93,0,111,114,105,103,105,110,79,112,116,115,0,112,110,116,115,119,0,111,112,110, -116,115,117,0,111,112,110,116,115,118,0,111,112,110,116,115,119,0,116,121,112,101,117,0,116,121,112,101,118,0,116,121, -112,101,119,0,102,117,0,102,118,0,102,119,0,100,117,0,100,118,0,100,119,0,42,100,101,102,0,118,101,99,91,56, -93,91,51,93,0,112,97,114,116,121,112,101,0,112,97,114,49,0,112,97,114,50,0,112,97,114,51,0,112,97,114,115, -117,98,115,116,114,91,51,50,93,0,42,116,114,97,99,107,0,42,112,114,111,120,121,0,42,112,114,111,120,121,95,103, -114,111,117,112,0,42,112,114,111,120,121,95,102,114,111,109,0,42,97,99,116,105,111,110,0,42,112,111,115,101,108,105, -98,0,42,112,111,115,101,0,99,111,110,115,116,114,97,105,110,116,67,104,97,110,110,101,108,115,0,100,101,102,98,97, -115,101,0,109,111,100,105,102,105,101,114,115,0,100,108,111,99,91,51,93,0,111,114,105,103,91,51,93,0,100,115,105, -122,101,91,51,93,0,100,114,111,116,91,51,93,0,111,98,109,97,116,91,52,93,91,52,93,0,99,111,110,115,116,105, -110,118,91,52,93,91,52,93,0,108,97,121,0,99,111,108,98,105,116,115,0,116,114,97,110,115,102,108,97,103,0,105, -112,111,102,108,97,103,0,116,114,97,99,107,102,108,97,103,0,117,112,102,108,97,103,0,110,108,97,102,108,97,103,0, -112,114,111,116,101,99,116,102,108,97,103,0,105,112,111,119,105,110,0,115,99,97,102,108,97,103,0,115,99,97,118,105, -115,102,108,97,103,0,98,111,117,110,100,116,121,112,101,0,100,117,112,111,110,0,100,117,112,111,102,102,0,100,117,112, -115,116,97,0,100,117,112,101,110,100,0,115,102,0,99,116,105,109,101,0,109,97,115,115,0,100,97,109,112,105,110,103, -0,105,110,101,114,116,105,97,0,102,111,114,109,102,97,99,116,111,114,0,114,100,97,109,112,105,110,103,0,115,105,122, -101,102,97,99,0,109,97,114,103,105,110,0,109,97,120,95,118,101,108,0,109,105,110,95,118,101,108,0,109,95,99,111, -110,116,97,99,116,80,114,111,99,101,115,115,105,110,103,84,104,114,101,115,104,111,108,100,0,100,116,0,100,116,120,0, -97,99,116,99,111,108,0,101,109,112,116,121,95,100,114,97,119,116,121,112,101,0,112,97,100,49,91,51,93,0,101,109, -112,116,121,95,100,114,97,119,115,105,122,101,0,100,117,112,102,97,99,101,115,99,97,0,112,114,111,112,0,115,101,110, -115,111,114,115,0,99,111,110,116,114,111,108,108,101,114,115,0,97,99,116,117,97,116,111,114,115,0,98,98,115,105,122, -101,91,51,93,0,97,99,116,100,101,102,0,103,97,109,101,102,108,97,103,0,103,97,109,101,102,108,97,103,50,0,42, -98,115,111,102,116,0,115,111,102,116,102,108,97,103,0,97,110,105,115,111,116,114,111,112,105,99,70,114,105,99,116,105, -111,110,91,51,93,0,99,111,110,115,116,114,97,105,110,116,115,0,110,108,97,115,116,114,105,112,115,0,104,111,111,107, -115,0,112,97,114,116,105,99,108,101,115,121,115,116,101,109,0,42,112,100,0,42,115,111,102,116,0,42,100,117,112,95, -103,114,111,117,112,0,102,108,117,105,100,115,105,109,70,108,97,103,0,114,101,115,116,114,105,99,116,102,108,97,103,0, -115,104,97,112,101,110,114,0,115,104,97,112,101,102,108,97,103,0,114,101,99,97,108,99,111,0,98,111,100,121,95,116, -121,112,101,0,42,102,108,117,105,100,115,105,109,83,101,116,116,105,110,103,115,0,42,100,101,114,105,118,101,100,68,101, -102,111,114,109,0,42,100,101,114,105,118,101,100,70,105,110,97,108,0,108,97,115,116,68,97,116,97,77,97,115,107,0, -115,116,97,116,101,0,105,110,105,116,95,115,116,97,116,101,0,103,112,117,108,97,109,112,0,99,117,114,105,110,100,101, -120,0,97,99,116,105,118,101,0,100,101,102,108,101,99,116,0,102,111,114,99,101,102,105,101,108,100,0,112,100,101,102, -95,100,97,109,112,0,112,100,101,102,95,114,100,97,109,112,0,112,100,101,102,95,112,101,114,109,0,112,100,101,102,95, -102,114,105,99,116,0,112,100,101,102,95,114,102,114,105,99,116,0,102,95,115,116,114,101,110,103,116,104,0,102,95,112, -111,119,101,114,0,102,95,100,105,115,116,0,102,95,100,97,109,112,0,109,97,120,100,105,115,116,0,109,105,110,100,105, -115,116,0,109,97,120,114,97,100,0,109,105,110,114,97,100,0,102,95,112,111,119,101,114,95,114,0,112,100,101,102,95, -115,98,100,97,109,112,0,112,100,101,102,95,115,98,105,102,116,0,112,100,101,102,95,115,98,111,102,116,0,99,108,117, -109,112,95,102,97,99,0,99,108,117,109,112,95,112,111,119,0,107,105,110,107,95,102,114,101,113,0,107,105,110,107,95, -115,104,97,112,101,0,107,105,110,107,95,97,109,112,0,102,114,101,101,95,101,110,100,0,116,101,120,95,110,97,98,108, -97,0,116,101,120,95,109,111,100,101,0,107,105,110,107,0,107,105,110,107,95,97,120,105,115,0,114,116,50,0,42,114, -110,103,0,102,95,110,111,105,115,101,0,115,105,109,102,114,97,109,101,0,115,116,97,114,116,102,114,97,109,101,0,101, -110,100,102,114,97,109,101,0,101,100,105,116,102,114,97,109,101,0,108,105,110,83,116,105,102,102,0,97,110,103,83,116, -105,102,102,0,118,111,108,117,109,101,0,118,105,116,101,114,97,116,105,111,110,115,0,112,105,116,101,114,97,116,105,111, -110,115,0,100,105,116,101,114,97,116,105,111,110,115,0,99,105,116,101,114,97,116,105,111,110,115,0,107,83,82,72,82, -95,67,76,0,107,83,75,72,82,95,67,76,0,107,83,83,72,82,95,67,76,0,107,83,82,95,83,80,76,84,95,67, -76,0,107,83,75,95,83,80,76,84,95,67,76,0,107,83,83,95,83,80,76,84,95,67,76,0,107,86,67,70,0,107, -68,80,0,107,68,71,0,107,76,70,0,107,80,82,0,107,86,67,0,107,68,70,0,107,77,84,0,107,67,72,82,0, -107,75,72,82,0,107,83,72,82,0,107,65,72,82,0,99,111,108,108,105,115,105,111,110,102,108,97,103,115,0,110,117, -109,99,108,117,115,116,101,114,105,116,101,114,97,116,105,111,110,115,0,119,101,108,100,105,110,103,0,42,112,97,114,116, -105,99,108,101,115,0,116,111,116,112,111,105,110,116,0,116,111,116,115,112,114,105,110,103,0,42,98,112,111,105,110,116, -0,42,98,115,112,114,105,110,103,0,109,115,103,95,108,111,99,107,0,109,115,103,95,118,97,108,117,101,0,110,111,100, -101,109,97,115,115,0,110,97,109,101,100,86,71,95,77,97,115,115,91,51,50,93,0,103,114,97,118,0,109,101,100,105, -97,102,114,105,99,116,0,114,107,108,105,109,105,116,0,112,104,121,115,105,99,115,95,115,112,101,101,100,0,103,111,97, -108,115,112,114,105,110,103,0,103,111,97,108,102,114,105,99,116,0,109,105,110,103,111,97,108,0,109,97,120,103,111,97, -108,0,100,101,102,103,111,97,108,0,118,101,114,116,103,114,111,117,112,0,110,97,109,101,100,86,71,95,83,111,102,116, -103,111,97,108,91,51,50,93,0,102,117,122,122,121,110,101,115,115,0,105,110,115,112,114,105,110,103,0,105,110,102,114, -105,99,116,0,110,97,109,101,100,86,71,95,83,112,114,105,110,103,95,75,91,51,50,93,0,101,102,114,97,0,105,110, -116,101,114,118,97,108,0,108,111,99,97,108,0,115,111,108,118,101,114,102,108,97,103,115,0,42,42,107,101,121,115,0, -116,111,116,112,111,105,110,116,107,101,121,0,115,101,99,111,110,100,115,112,114,105,110,103,0,99,111,108,98,97,108,108, -0,98,97,108,108,100,97,109,112,0,98,97,108,108,115,116,105,102,102,0,115,98,99,95,109,111,100,101,0,97,101,114, -111,101,100,103,101,0,109,105,110,108,111,111,112,115,0,109,97,120,108,111,111,112,115,0,99,104,111,107,101,0,115,111, -108,118,101,114,95,73,68,0,112,108,97,115,116,105,99,0,115,112,114,105,110,103,112,114,101,108,111,97,100,0,42,115, -99,114,97,116,99,104,0,115,104,101,97,114,115,116,105,102,102,0,105,110,112,117,115,104,0,42,112,111,105,110,116,99, -97,99,104,101,0,115,104,111,119,95,97,100,118,97,110,99,101,100,111,112,116,105,111,110,115,0,114,101,115,111,108,117, -116,105,111,110,120,121,122,0,112,114,101,118,105,101,119,114,101,115,120,121,122,0,114,101,97,108,115,105,122,101,0,103, -117,105,68,105,115,112,108,97,121,77,111,100,101,0,114,101,110,100,101,114,68,105,115,112,108,97,121,77,111,100,101,0, -118,105,115,99,111,115,105,116,121,86,97,108,117,101,0,118,105,115,99,111,115,105,116,121,77,111,100,101,0,118,105,115, -99,111,115,105,116,121,69,120,112,111,110,101,110,116,0,103,114,97,118,120,0,103,114,97,118,121,0,103,114,97,118,122, -0,97,110,105,109,83,116,97,114,116,0,97,110,105,109,69,110,100,0,103,115,116,97,114,0,109,97,120,82,101,102,105, -110,101,0,105,110,105,86,101,108,120,0,105,110,105,86,101,108,121,0,105,110,105,86,101,108,122,0,42,111,114,103,77, -101,115,104,0,42,109,101,115,104,83,117,114,102,97,99,101,0,42,109,101,115,104,66,66,0,115,117,114,102,100,97,116, -97,80,97,116,104,91,50,52,48,93,0,98,98,83,116,97,114,116,91,51,93,0,98,98,83,105,122,101,91,51,93,0, -116,121,112,101,70,108,97,103,115,0,100,111,109,97,105,110,78,111,118,101,99,103,101,110,0,118,111,108,117,109,101,73, -110,105,116,84,121,112,101,0,112,97,114,116,83,108,105,112,86,97,108,117,101,0,103,101,110,101,114,97,116,101,84,114, -97,99,101,114,115,0,103,101,110,101,114,97,116,101,80,97,114,116,105,99,108,101,115,0,115,117,114,102,97,99,101,83, -109,111,111,116,104,105,110,103,0,115,117,114,102,97,99,101,83,117,98,100,105,118,115,0,112,97,114,116,105,99,108,101, -73,110,102,83,105,122,101,0,112,97,114,116,105,99,108,101,73,110,102,65,108,112,104,97,0,102,97,114,70,105,101,108, -100,83,105,122,101,0,42,109,101,115,104,83,117,114,102,78,111,114,109,97,108,115,0,99,112,115,84,105,109,101,83,116, -97,114,116,0,99,112,115,84,105,109,101,69,110,100,0,99,112,115,81,117,97,108,105,116,121,0,97,116,116,114,97,99, -116,102,111,114,99,101,83,116,114,101,110,103,116,104,0,97,116,116,114,97,99,116,102,111,114,99,101,82,97,100,105,117, -115,0,118,101,108,111,99,105,116,121,102,111,114,99,101,83,116,114,101,110,103,116,104,0,118,101,108,111,99,105,116,121, -102,111,114,99,101,82,97,100,105,117,115,0,108,97,115,116,103,111,111,100,102,114,97,109,101,0,109,105,115,116,121,112, -101,0,104,111,114,114,0,104,111,114,103,0,104,111,114,98,0,104,111,114,107,0,122,101,110,114,0,122,101,110,103,0, -122,101,110,98,0,122,101,110,107,0,97,109,98,107,0,102,97,115,116,99,111,108,0,101,120,112,111,115,117,114,101,0, -101,120,112,0,114,97,110,103,101,0,108,105,110,102,97,99,0,108,111,103,102,97,99,0,103,114,97,118,105,116,121,0, -97,99,116,105,118,105,116,121,66,111,120,82,97,100,105,117,115,0,115,107,121,116,121,112,101,0,111,99,99,108,117,115, -105,111,110,82,101,115,0,112,104,121,115,105,99,115,69,110,103,105,110,101,0,116,105,99,114,97,116,101,0,109,97,120, -108,111,103,105,99,115,116,101,112,0,112,104,121,115,117,98,115,116,101,112,0,109,97,120,112,104,121,115,116,101,112,0, -109,105,115,105,0,109,105,115,116,115,116,97,0,109,105,115,116,100,105,115,116,0,109,105,115,116,104,105,0,115,116,97, -114,114,0,115,116,97,114,103,0,115,116,97,114,98,0,115,116,97,114,107,0,115,116,97,114,115,105,122,101,0,115,116, -97,114,109,105,110,100,105,115,116,0,115,116,97,114,100,105,115,116,0,115,116,97,114,99,111,108,110,111,105,115,101,0, -100,111,102,115,116,97,0,100,111,102,101,110,100,0,100,111,102,109,105,110,0,100,111,102,109,97,120,0,97,111,100,105, -115,116,0,97,111,100,105,115,116,102,97,99,0,97,111,101,110,101,114,103,121,0,97,111,98,105,97,115,0,97,111,109, -111,100,101,0,97,111,115,97,109,112,0,97,111,109,105,120,0,97,111,99,111,108,111,114,0,97,111,95,97,100,97,112, -116,95,116,104,114,101,115,104,0,97,111,95,97,100,97,112,116,95,115,112,101,101,100,95,102,97,99,0,97,111,95,97, -112,112,114,111,120,95,101,114,114,111,114,0,97,111,95,97,112,112,114,111,120,95,99,111,114,114,101,99,116,105,111,110, -0,97,111,95,115,97,109,112,95,109,101,116,104,111,100,0,97,111,95,103,97,116,104,101,114,95,109,101,116,104,111,100, -0,97,111,95,97,112,112,114,111,120,95,112,97,115,115,101,115,0,42,97,111,115,112,104,101,114,101,0,42,97,111,116, -97,98,108,101,115,0,104,101,109,105,114,101,115,0,109,97,120,105,116,101,114,0,100,114,97,119,116,121,112,101,0,115, -117,98,115,104,111,111,116,112,0,115,117,98,115,104,111,111,116,101,0,110,111,100,101,108,105,109,0,109,97,120,115,117, -98,108,97,109,112,0,112,97,109,97,0,112,97,109,105,0,101,108,109,97,0,101,108,109,105,0,109,97,120,110,111,100, -101,0,99,111,110,118,101,114,103,101,110,99,101,0,114,97,100,102,97,99,0,103,97,109,109,97,0,115,101,108,99,111, -108,0,115,120,0,115,121,0,42,108,112,70,111,114,109,97,116,0,42,108,112,80,97,114,109,115,0,99,98,70,111,114, -109,97,116,0,99,98,80,97,114,109,115,0,102,99,99,84,121,112,101,0,102,99,99,72,97,110,100,108,101,114,0,100, -119,75,101,121,70,114,97,109,101,69,118,101,114,121,0,100,119,81,117,97,108,105,116,121,0,100,119,66,121,116,101,115, -80,101,114,83,101,99,111,110,100,0,100,119,70,108,97,103,115,0,100,119,73,110,116,101,114,108,101,97,118,101,69,118, -101,114,121,0,97,118,105,99,111,100,101,99,110,97,109,101,91,49,50,56,93,0,42,99,100,80,97,114,109,115,0,42, -112,97,100,0,99,100,83,105,122,101,0,113,116,99,111,100,101,99,110,97,109,101,91,49,50,56,93,0,99,111,100,101, -99,0,97,117,100,105,111,95,99,111,100,101,99,0,118,105,100,101,111,95,98,105,116,114,97,116,101,0,97,117,100,105, -111,95,98,105,116,114,97,116,101,0,103,111,112,95,115,105,122,101,0,114,99,95,109,105,110,95,114,97,116,101,0,114, -99,95,109,97,120,95,114,97,116,101,0,114,99,95,98,117,102,102,101,114,95,115,105,122,101,0,109,117,120,95,112,97, -99,107,101,116,95,115,105,122,101,0,109,117,120,95,114,97,116,101,0,109,105,120,114,97,116,101,0,109,97,105,110,0, -42,109,97,116,95,111,118,101,114,114,105,100,101,0,42,108,105,103,104,116,95,111,118,101,114,114,105,100,101,0,108,97, -121,95,122,109,97,115,107,0,108,97,121,102,108,97,103,0,112,97,115,115,102,108,97,103,0,112,97,115,115,95,120,111, -114,0,42,97,118,105,99,111,100,101,99,100,97,116,97,0,42,113,116,99,111,100,101,99,100,97,116,97,0,102,102,99, -111,100,101,99,100,97,116,97,0,99,102,114,97,0,112,115,102,114,97,0,112,101,102,114,97,0,105,109,97,103,101,115, -0,102,114,97,109,97,112,116,111,0,116,104,114,101,97,100,115,0,102,114,97,109,101,108,101,110,0,98,108,117,114,102, -97,99,0,101,100,103,101,82,0,101,100,103,101,71,0,101,100,103,101,66,0,102,117,108,108,115,99,114,101,101,110,0, -120,112,108,97,121,0,121,112,108,97,121,0,102,114,101,113,112,108,97,121,0,97,116,116,114,105,98,0,114,116,49,0, -115,116,101,114,101,111,109,111,100,101,0,100,105,109,101,110,115,105,111,110,115,112,114,101,115,101,116,0,109,97,120,105, -109,115,105,122,101,0,120,115,99,104,0,121,115,99,104,0,120,112,97,114,116,115,0,121,112,97,114,116,115,0,119,105, -110,112,111,115,0,112,108,97,110,101,115,0,105,109,116,121,112,101,0,115,117,98,105,109,116,121,112,101,0,113,117,97, -108,105,116,121,0,114,112,97,100,0,114,112,97,100,49,0,114,112,97,100,50,0,115,99,101,109,111,100,101,0,114,101, -110,100,101,114,101,114,0,111,99,114,101,115,0,97,108,112,104,97,109,111,100,101,0,111,115,97,0,102,114,115,95,115, -101,99,0,101,100,103,101,105,110,116,0,115,97,102,101,116,121,0,98,111,114,100,101,114,0,100,105,115,112,114,101,99, -116,0,108,97,121,101,114,115,0,97,99,116,108,97,121,0,120,97,115,112,0,121,97,115,112,0,102,114,115,95,115,101, -99,95,98,97,115,101,0,103,97,117,115,115,0,112,111,115,116,109,117,108,0,112,111,115,116,103,97,109,109,97,0,112, -111,115,116,104,117,101,0,112,111,115,116,115,97,116,0,100,105,116,104,101,114,95,105,110,116,101,110,115,105,116,121,0, -98,97,107,101,95,111,115,97,0,98,97,107,101,95,102,105,108,116,101,114,0,98,97,107,101,95,109,111,100,101,0,98, -97,107,101,95,102,108,97,103,0,98,97,107,101,95,110,111,114,109,97,108,95,115,112,97,99,101,0,98,97,107,101,95, -113,117,97,100,95,115,112,108,105,116,0,98,97,107,101,95,109,97,120,100,105,115,116,0,98,97,107,101,95,98,105,97, -115,100,105,115,116,0,98,97,107,101,95,112,97,100,0,71,73,113,117,97,108,105,116,121,0,71,73,99,97,99,104,101, -0,71,73,109,101,116,104,111,100,0,71,73,112,104,111,116,111,110,115,0,71,73,100,105,114,101,99,116,0,89,70,95, -65,65,0,89,70,101,120,112,111,114,116,120,109,108,0,89,70,95,110,111,98,117,109,112,0,89,70,95,99,108,97,109, -112,114,103,98,0,121,102,112,97,100,49,0,71,73,100,101,112,116,104,0,71,73,99,97,117,115,100,101,112,116,104,0, -71,73,112,105,120,101,108,115,112,101,114,115,97,109,112,108,101,0,71,73,112,104,111,116,111,110,99,111,117,110,116,0, -71,73,109,105,120,112,104,111,116,111,110,115,0,71,73,112,104,111,116,111,110,114,97,100,105,117,115,0,89,70,95,114, -97,121,100,101,112,116,104,0,89,70,95,65,65,112,97,115,115,101,115,0,89,70,95,65,65,115,97,109,112,108,101,115, -0,121,102,112,97,100,50,0,71,73,115,104,97,100,111,119,113,117,97,108,105,116,121,0,71,73,114,101,102,105,110,101, -109,101,110,116,0,71,73,112,111,119,101,114,0,71,73,105,110,100,105,114,112,111,119,101,114,0,89,70,95,103,97,109, -109,97,0,89,70,95,101,120,112,111,115,117,114,101,0,89,70,95,114,97,121,98,105,97,115,0,89,70,95,65,65,112, -105,120,101,108,115,105,122,101,0,89,70,95,65,65,116,104,114,101,115,104,111,108,100,0,98,97,99,107,98,117,102,91, -49,54,48,93,0,112,105,99,91,49,54,48,93,0,115,116,97,109,112,0,115,116,97,109,112,95,102,111,110,116,95,105, -100,0,115,116,97,109,112,95,117,100,97,116,97,91,49,54,48,93,0,102,103,95,115,116,97,109,112,91,52,93,0,98, -103,95,115,116,97,109,112,91,52,93,0,115,105,109,112,108,105,102,121,95,115,117,98,115,117,114,102,0,115,105,109,112, -108,105,102,121,95,115,104,97,100,111,119,115,97,109,112,108,101,115,0,115,105,109,112,108,105,102,121,95,112,97,114,116, -105,99,108,101,115,0,115,105,109,112,108,105,102,121,95,97,111,115,115,115,0,99,105,110,101,111,110,119,104,105,116,101, -0,99,105,110,101,111,110,98,108,97,99,107,0,99,105,110,101,111,110,103,97,109,109,97,0,106,112,50,95,112,114,101, -115,101,116,0,106,112,50,95,100,101,112,116,104,0,114,112,97,100,51,0,100,111,109,101,114,101,115,0,100,111,109,101, -109,111,100,101,0,100,111,109,101,97,110,103,108,101,0,100,111,109,101,116,105,108,116,0,100,111,109,101,114,101,115,98, -117,102,0,42,100,111,109,101,116,101,120,116,0,112,97,114,116,105,99,108,101,95,112,101,114,99,0,115,117,98,115,117, -114,102,95,109,97,120,0,115,104,97,100,98,117,102,115,97,109,112,108,101,95,109,97,120,0,97,111,95,101,114,114,111, -114,0,99,111,108,91,51,93,0,102,114,97,109,101,0,110,97,109,101,91,54,52,93,0,42,98,114,117,115,104,0,116, -111,111,108,0,115,101,97,109,95,98,108,101,101,100,0,110,111,114,109,97,108,95,97,110,103,108,101,0,115,116,101,112, -0,105,110,118,101,114,116,0,116,111,116,114,101,107,101,121,0,116,111,116,97,100,100,107,101,121,0,98,114,117,115,104, -116,121,112,101,0,98,114,117,115,104,91,55,93,0,101,109,105,116,116,101,114,100,105,115,116,0,100,114,97,119,95,116, -105,109,101,100,0,110,97,109,101,91,51,54,93,0,109,97,116,91,51,93,91,51,93,0,99,111,114,110,101,114,116,121, -112,101,0,101,100,105,116,98,117,116,102,108,97,103,0,106,111,105,110,116,114,105,108,105,109,105,116,0,100,101,103,114, -0,116,117,114,110,0,101,120,116,114,95,111,102,102,115,0,100,111,117,98,108,105,109,105,116,0,115,101,103,109,101,110, -116,115,0,114,105,110,103,115,0,118,101,114,116,105,99,101,115,0,117,110,119,114,97,112,112,101,114,0,117,118,99,97, -108,99,95,114,97,100,105,117,115,0,117,118,99,97,108,99,95,99,117,98,101,115,105,122,101,0,117,118,99,97,108,99, -95,109,97,114,103,105,110,0,117,118,99,97,108,99,95,109,97,112,100,105,114,0,117,118,99,97,108,99,95,109,97,112, -97,108,105,103,110,0,117,118,99,97,108,99,95,102,108,97,103,0,97,117,116,111,105,107,95,99,104,97,105,110,108,101, -110,0,105,109,97,112,97,105,110,116,0,112,97,114,116,105,99,108,101,0,115,101,108,101,99,116,95,116,104,114,101,115, -104,0,99,108,101,97,110,95,116,104,114,101,115,104,0,114,101,116,111,112,111,95,109,111,100,101,0,114,101,116,111,112, -111,95,112,97,105,110,116,95,116,111,111,108,0,108,105,110,101,95,100,105,118,0,101,108,108,105,112,115,101,95,100,105, -118,0,114,101,116,111,112,111,95,104,111,116,115,112,111,116,0,109,117,108,116,105,114,101,115,95,115,117,98,100,105,118, -95,116,121,112,101,0,115,107,103,101,110,95,114,101,115,111,108,117,116,105,111,110,0,115,107,103,101,110,95,116,104,114, -101,115,104,111,108,100,95,105,110,116,101,114,110,97,108,0,115,107,103,101,110,95,116,104,114,101,115,104,111,108,100,95, -101,120,116,101,114,110,97,108,0,115,107,103,101,110,95,108,101,110,103,116,104,95,114,97,116,105,111,0,115,107,103,101, -110,95,108,101,110,103,116,104,95,108,105,109,105,116,0,115,107,103,101,110,95,97,110,103,108,101,95,108,105,109,105,116, -0,115,107,103,101,110,95,99,111,114,114,101,108,97,116,105,111,110,95,108,105,109,105,116,0,115,107,103,101,110,95,115, -121,109,109,101,116,114,121,95,108,105,109,105,116,0,115,107,103,101,110,95,114,101,116,97,114,103,101,116,95,97,110,103, -108,101,95,119,101,105,103,104,116,0,115,107,103,101,110,95,114,101,116,97,114,103,101,116,95,108,101,110,103,116,104,95, -119,101,105,103,104,116,0,115,107,103,101,110,95,114,101,116,97,114,103,101,116,95,100,105,115,116,97,110,99,101,95,119, -101,105,103,104,116,0,115,107,103,101,110,95,111,112,116,105,111,110,115,0,115,107,103,101,110,95,112,111,115,116,112,114, -111,0,115,107,103,101,110,95,112,111,115,116,112,114,111,95,112,97,115,115,101,115,0,115,107,103,101,110,95,115,117,98, -100,105,118,105,115,105,111,110,115,91,51,93,0,115,107,103,101,110,95,109,117,108,116,105,95,108,101,118,101,108,0,42, -115,107,103,101,110,95,116,101,109,112,108,97,116,101,0,98,111,110,101,95,115,107,101,116,99,104,105,110,103,0,98,111, -110,101,95,115,107,101,116,99,104,105,110,103,95,99,111,110,118,101,114,116,0,115,107,103,101,110,95,115,117,98,100,105, -118,105,115,105,111,110,95,110,117,109,98,101,114,0,115,107,103,101,110,95,114,101,116,97,114,103,101,116,95,111,112,116, -105,111,110,115,0,115,107,103,101,110,95,114,101,116,97,114,103,101,116,95,114,111,108,108,0,115,107,103,101,110,95,115, -105,100,101,95,115,116,114,105,110,103,91,56,93,0,115,107,103,101,110,95,110,117,109,95,115,116,114,105,110,103,91,56, -93,0,101,100,103,101,95,109,111,100,101,0,112,97,100,51,91,50,93,0,100,105,114,0,118,105,101,119,0,42,115,101, -115,115,105,111,110,0,42,99,117,109,97,112,0,100,114,97,119,98,114,117,115,104,0,115,109,111,111,116,104,98,114,117, -115,104,0,112,105,110,99,104,98,114,117,115,104,0,105,110,102,108,97,116,101,98,114,117,115,104,0,103,114,97,98,98, -114,117,115,104,0,108,97,121,101,114,98,114,117,115,104,0,102,108,97,116,116,101,110,98,114,117,115,104,0,112,105,118, -111,116,91,51,93,0,98,114,117,115,104,95,116,121,112,101,0,116,101,120,110,114,0,116,101,120,114,101,112,116,0,116, -101,120,102,97,100,101,0,116,101,120,115,101,112,0,97,118,101,114,97,103,105,110,103,0,116,97,98,108,101,116,95,115, -105,122,101,0,116,97,98,108,101,116,95,115,116,114,101,110,103,116,104,0,115,121,109,109,0,114,97,107,101,0,97,120, -105,115,108,111,99,107,0,42,99,97,109,101,114,97,0,42,119,111,114,108,100,0,42,115,101,116,0,98,97,115,101,0, -42,98,97,115,97,99,116,0,99,117,114,115,111,114,91,51,93,0,116,119,99,101,110,116,91,51,93,0,116,119,109,105, -110,91,51,93,0,116,119,109,97,120,91,51,93,0,101,100,105,116,98,117,116,115,105,122,101,0,115,101,108,101,99,116, -109,111,100,101,0,112,114,111,112,111,114,116,105,111,110,97,108,0,112,114,111,112,95,109,111,100,101,0,97,117,116,111, -109,101,114,103,101,0,112,97,100,53,0,112,97,100,54,0,97,117,116,111,107,101,121,95,109,111,100,101,0,42,101,100, -0,42,114,97,100,105,111,0,102,114,97,109,105,110,103,0,42,116,111,111,108,115,101,116,116,105,110,103,115,0,97,117, -100,105,111,0,116,114,97,110,115,102,111,114,109,95,115,112,97,99,101,115,0,106,117,109,112,102,114,97,109,101,0,115, -110,97,112,95,109,111,100,101,0,115,110,97,112,95,102,108,97,103,0,115,110,97,112,95,116,97,114,103,101,116,0,42, -116,104,101,68,97,103,0,100,97,103,105,115,118,97,108,105,100,0,100,97,103,102,108,97,103,115,0,115,99,117,108,112, -116,100,97,116,97,0,102,114,97,109,101,95,115,116,101,112,0,122,111,111,109,0,98,108,101,110,100,0,120,105,109,0, -121,105,109,0,115,112,97,99,101,116,121,112,101,0,98,108,111,99,107,115,99,97,108,101,0,42,97,114,101,97,0,98, -108,111,99,107,104,97,110,100,108,101,114,91,56,93,0,118,105,101,119,109,97,116,91,52,93,91,52,93,0,118,105,101, -119,105,110,118,91,52,93,91,52,93,0,112,101,114,115,109,97,116,91,52,93,91,52,93,0,112,101,114,115,105,110,118, -91,52,93,91,52,93,0,119,105,110,109,97,116,49,91,52,93,91,52,93,0,118,105,101,119,109,97,116,49,91,52,93, -91,52,93,0,118,105,101,119,113,117,97,116,91,52,93,0,122,102,97,99,0,108,97,121,95,117,115,101,100,0,112,101, -114,115,112,0,42,111,98,95,99,101,110,116,114,101,0,42,98,103,112,105,99,0,42,108,111,99,97,108,118,100,0,42, -114,105,0,42,114,101,116,111,112,111,95,118,105,101,119,95,100,97,116,97,0,42,100,101,112,116,104,115,0,111,98,95, -99,101,110,116,114,101,95,98,111,110,101,91,51,50,93,0,108,111,99,97,108,118,105,101,119,0,108,97,121,97,99,116, -0,115,99,101,110,101,108,111,99,107,0,97,114,111,117,110,100,0,99,97,109,122,111,111,109,0,112,105,118,111,116,95, -108,97,115,116,0,103,114,105,100,0,103,114,105,100,118,105,101,119,0,112,105,120,115,105,122,101,0,110,101,97,114,0, -102,97,114,0,99,97,109,100,120,0,99,97,109,100,121,0,103,114,105,100,108,105,110,101,115,0,118,105,101,119,98,117, -116,0,103,114,105,100,102,108,97,103,0,109,111,100,101,115,101,108,101,99,116,0,116,119,116,121,112,101,0,116,119,109, -111,100,101,0,116,119,102,108,97,103,0,116,119,100,114,97,119,102,108,97,103,0,116,119,109,97,116,91,52,93,91,52, -93,0,99,108,105,112,91,52,93,91,52,93,0,42,99,108,105,112,98,98,0,97,102,116,101,114,100,114,97,119,0,122, -98,117,102,0,120,114,97,121,0,102,108,97,103,50,0,103,114,105,100,115,117,98,100,105,118,0,107,101,121,102,108,97, -103,115,0,110,100,111,102,109,111,100,101,0,110,100,111,102,102,105,108,116,101,114,0,42,112,114,111,112,101,114,116,105, -101,115,95,115,116,111,114,97,103,101,0,42,103,112,100,0,108,118,105,101,119,113,117,97,116,91,52,93,0,108,112,101, -114,115,112,0,108,118,105,101,119,0,118,101,114,116,0,104,111,114,0,109,97,115,107,0,109,105,110,91,50,93,0,109, -97,120,91,50,93,0,109,105,110,122,111,111,109,0,109,97,120,122,111,111,109,0,115,99,114,111,108,108,0,107,101,101, -112,116,111,116,0,107,101,101,112,97,115,112,101,99,116,0,107,101,101,112,122,111,111,109,0,111,108,100,119,105,110,120, -0,111,108,100,119,105,110,121,0,99,117,114,115,111,114,91,50,93,0,114,111,119,98,117,116,0,118,50,100,0,42,101, -100,105,116,105,112,111,0,105,112,111,107,101,121,0,97,99,116,110,97,109,101,91,51,50,93,0,99,111,110,115,116,110, -97,109,101,91,51,50,93,0,98,111,110,101,110,97,109,101,91,51,50,93,0,116,111,116,105,112,111,0,112,105,110,0, -98,117,116,111,102,115,0,99,104,97,110,110,101,108,0,108,111,99,107,0,109,101,100,105,97,110,91,51,93,0,99,117, -114,115,101,110,115,0,99,117,114,97,99,116,0,97,108,105,103,110,0,116,97,98,111,0,109,97,105,110,98,0,109,97, -105,110,98,111,0,42,108,111,99,107,112,111,105,110,0,116,101,120,102,114,111,109,0,115,104,111,119,103,114,111,117,112, -0,109,111,100,101,108,116,121,112,101,0,115,99,114,105,112,116,98,108,111,99,107,0,114,101,95,97,108,105,103,110,0, -111,108,100,107,101,121,112,114,101,115,115,0,116,97,98,91,55,93,0,114,101,110,100,101,114,95,115,105,122,101,0,99, -104,97,110,115,104,111,119,110,0,122,101,98,114,97,0,42,102,105,108,101,108,105,115,116,0,116,111,116,102,105,108,101, -0,116,105,116,108,101,91,50,52,93,0,100,105,114,91,50,52,48,93,0,102,105,108,101,91,56,48,93,0,111,102,115, -0,115,111,114,116,0,109,97,120,110,97,109,101,108,101,110,0,99,111,108,108,117,109,115,0,102,95,102,112,0,102,112, -95,115,116,114,91,56,93,0,42,108,105,98,102,105,108,101,100,97,116,97,0,114,101,116,118,97,108,0,109,101,110,117, -0,97,99,116,0,40,42,114,101,116,117,114,110,102,117,110,99,41,40,41,0,40,42,114,101,116,117,114,110,102,117,110, -99,95,101,118,101,110,116,41,40,41,0,40,42,114,101,116,117,114,110,102,117,110,99,95,97,114,103,115,41,40,41,0, -42,97,114,103,49,0,42,97,114,103,50,0,42,109,101,110,117,112,0,42,112,117,112,109,101,110,117,0,111,111,112,115, -0,118,105,115,105,102,108,97,103,0,116,114,101,101,0,42,116,114,101,101,115,116,111,114,101,0,115,101,97,114,99,104, -95,115,116,114,105,110,103,91,51,50,93,0,115,101,97,114,99,104,95,116,115,101,0,115,101,97,114,99,104,95,102,108, -97,103,115,0,100,111,95,0,111,117,116,108,105,110,101,118,105,115,0,115,116,111,114,101,102,108,97,103,0,100,101,112, -115,95,102,108,97,103,115,0,105,109,97,110,114,0,99,117,114,116,105,108,101,0,105,109,116,121,112,101,110,114,0,100, -116,95,117,118,0,115,116,105,99,107,121,0,100,116,95,117,118,115,116,114,101,116,99,104,0,112,97,100,91,53,93,0, -99,101,110,116,120,0,99,101,110,116,121,0,97,117,116,111,115,110,97,112,0,42,116,101,120,116,0,116,111,112,0,118, -105,101,119,108,105,110,101,115,0,102,111,110,116,95,105,100,0,108,104,101,105,103,104,116,0,108,101,102,116,0,115,104, -111,119,108,105,110,101,110,114,115,0,116,97,98,110,117,109,98,101,114,0,99,117,114,114,116,97,98,95,115,101,116,0, -115,104,111,119,115,121,110,116,97,120,0,111,118,101,114,119,114,105,116,101,0,112,105,120,95,112,101,114,95,108,105,110, -101,0,116,120,116,115,99,114,111,108,108,0,116,120,116,98,97,114,0,119,111,114,100,119,114,97,112,0,100,111,112,108, -117,103,105,110,115,0,42,112,121,95,100,114,97,119,0,42,112,121,95,101,118,101,110,116,0,42,112,121,95,98,117,116, -116,111,110,0,42,112,121,95,98,114,111,119,115,101,114,99,97,108,108,98,97,99,107,0,42,112,121,95,103,108,111,98, -97,108,100,105,99,116,0,108,97,115,116,115,112,97,99,101,0,115,99,114,105,112,116,110,97,109,101,91,50,53,54,93, -0,115,99,114,105,112,116,97,114,103,91,50,53,54,93,0,42,115,99,114,105,112,116,0,42,98,117,116,95,114,101,102, -115,0,114,101,100,114,97,119,115,0,42,105,100,0,97,115,112,101,99,116,0,42,99,117,114,102,111,110,116,0,42,101, -100,105,116,116,114,101,101,0,116,114,101,101,116,121,112,101,0,42,102,105,108,101,115,0,97,99,116,105,118,101,95,102, -105,108,101,0,110,117,109,116,105,108,101,115,120,0,110,117,109,116,105,108,101,115,121,0,115,101,108,115,116,97,116,101, -0,118,105,101,119,114,101,99,116,0,98,111,111,107,109,97,114,107,114,101,99,116,0,115,99,114,111,108,108,112,111,115, -0,115,99,114,111,108,108,104,101,105,103,104,116,0,115,99,114,111,108,108,97,114,101,97,0,97,99,116,105,118,101,95, -98,111,111,107,109,97,114,107,0,112,114,118,95,119,0,112,114,118,95,104,0,42,105,109,103,0,111,117,116,108,105,110, -101,91,52,93,0,110,101,117,116,114,97,108,91,52,93,0,97,99,116,105,111,110,91,52,93,0,115,101,116,116,105,110, -103,91,52,93,0,115,101,116,116,105,110,103,49,91,52,93,0,115,101,116,116,105,110,103,50,91,52,93,0,110,117,109, -91,52,93,0,116,101,120,116,102,105,101,108,100,91,52,93,0,116,101,120,116,102,105,101,108,100,95,104,105,91,52,93, -0,112,111,112,117,112,91,52,93,0,116,101,120,116,91,52,93,0,116,101,120,116,95,104,105,91,52,93,0,109,101,110, -117,95,98,97,99,107,91,52,93,0,109,101,110,117,95,105,116,101,109,91,52,93,0,109,101,110,117,95,104,105,108,105, -116,101,91,52,93,0,109,101,110,117,95,116,101,120,116,91,52,93,0,109,101,110,117,95,116,101,120,116,95,104,105,91, -52,93,0,98,117,116,95,100,114,97,119,116,121,112,101,0,105,99,111,110,102,105,108,101,91,56,48,93,0,98,97,99, -107,91,52,93,0,104,101,97,100,101,114,91,52,93,0,112,97,110,101,108,91,52,93,0,115,104,97,100,101,49,91,52, -93,0,115,104,97,100,101,50,91,52,93,0,104,105,108,105,116,101,91,52,93,0,103,114,105,100,91,52,93,0,119,105, -114,101,91,52,93,0,115,101,108,101,99,116,91,52,93,0,108,97,109,112,91,52,93,0,97,99,116,105,118,101,91,52, -93,0,103,114,111,117,112,91,52,93,0,103,114,111,117,112,95,97,99,116,105,118,101,91,52,93,0,116,114,97,110,115, -102,111,114,109,91,52,93,0,118,101,114,116,101,120,91,52,93,0,118,101,114,116,101,120,95,115,101,108,101,99,116,91, -52,93,0,101,100,103,101,91,52,93,0,101,100,103,101,95,115,101,108,101,99,116,91,52,93,0,101,100,103,101,95,115, -101,97,109,91,52,93,0,101,100,103,101,95,115,104,97,114,112,91,52,93,0,101,100,103,101,95,102,97,99,101,115,101, -108,91,52,93,0,102,97,99,101,91,52,93,0,102,97,99,101,95,115,101,108,101,99,116,91,52,93,0,102,97,99,101, -95,100,111,116,91,52,93,0,110,111,114,109,97,108,91,52,93,0,98,111,110,101,95,115,111,108,105,100,91,52,93,0, -98,111,110,101,95,112,111,115,101,91,52,93,0,115,116,114,105,112,91,52,93,0,115,116,114,105,112,95,115,101,108,101, -99,116,91,52,93,0,99,102,114,97,109,101,91,52,93,0,118,101,114,116,101,120,95,115,105,122,101,0,102,97,99,101, -100,111,116,95,115,105,122,101,0,98,112,97,100,91,50,93,0,115,121,110,116,97,120,108,91,52,93,0,115,121,110,116, -97,120,110,91,52,93,0,115,121,110,116,97,120,98,91,52,93,0,115,121,110,116,97,120,118,91,52,93,0,115,121,110, -116,97,120,99,91,52,93,0,109,111,118,105,101,91,52,93,0,105,109,97,103,101,91,52,93,0,115,99,101,110,101,91, -52,93,0,97,117,100,105,111,91,52,93,0,101,102,102,101,99,116,91,52,93,0,112,108,117,103,105,110,91,52,93,0, -116,114,97,110,115,105,116,105,111,110,91,52,93,0,109,101,116,97,91,52,93,0,101,100,105,116,109,101,115,104,95,97, -99,116,105,118,101,91,52,93,0,104,97,110,100,108,101,95,118,101,114,116,101,120,91,52,93,0,104,97,110,100,108,101, -95,118,101,114,116,101,120,95,115,101,108,101,99,116,91,52,93,0,104,97,110,100,108,101,95,118,101,114,116,101,120,95, -115,105,122,101,0,104,112,97,100,91,55,93,0,115,111,108,105,100,91,52,93,0,116,117,105,0,116,98,117,116,115,0, -116,118,51,100,0,116,102,105,108,101,0,116,105,112,111,0,116,105,110,102,111,0,116,115,110,100,0,116,97,99,116,0, -116,110,108,97,0,116,115,101,113,0,116,105,109,97,0,116,105,109,97,115,101,108,0,116,101,120,116,0,116,111,111,112, -115,0,116,116,105,109,101,0,116,110,111,100,101,0,116,97,114,109,91,50,48,93,0,98,112,97,100,91,52,93,0,98, -112,97,100,49,91,52,93,0,115,112,101,99,91,52,93,0,100,117,112,102,108,97,103,0,115,97,118,101,116,105,109,101, -0,116,101,109,112,100,105,114,91,49,54,48,93,0,102,111,110,116,100,105,114,91,49,54,48,93,0,114,101,110,100,101, -114,100,105,114,91,49,54,48,93,0,116,101,120,116,117,100,105,114,91,49,54,48,93,0,112,108,117,103,116,101,120,100, -105,114,91,49,54,48,93,0,112,108,117,103,115,101,113,100,105,114,91,49,54,48,93,0,112,121,116,104,111,110,100,105, -114,91,49,54,48,93,0,115,111,117,110,100,100,105,114,91,49,54,48,93,0,121,102,101,120,112,111,114,116,100,105,114, -91,49,54,48,93,0,118,101,114,115,105,111,110,115,0,118,114,109,108,102,108,97,103,0,103,97,109,101,102,108,97,103, -115,0,119,104,101,101,108,108,105,110,101,115,99,114,111,108,108,0,117,105,102,108,97,103,0,108,97,110,103,117,97,103, -101,0,117,115,101,114,112,114,101,102,0,118,105,101,119,122,111,111,109,0,99,111,110,115,111,108,101,95,98,117,102,102, -101,114,0,99,111,110,115,111,108,101,95,111,117,116,0,109,105,120,98,117,102,115,105,122,101,0,102,111,110,116,115,105, -122,101,0,101,110,99,111,100,105,110,103,0,116,114,97,110,115,111,112,116,115,0,109,101,110,117,116,104,114,101,115,104, -111,108,100,49,0,109,101,110,117,116,104,114,101,115,104,111,108,100,50,0,102,111,110,116,110,97,109,101,91,50,53,54, -93,0,116,104,101,109,101,115,0,117,110,100,111,115,116,101,112,115,0,117,110,100,111,109,101,109,111,114,121,0,103,112, -95,109,97,110,104,97,116,116,101,110,100,105,115,116,0,103,112,95,101,117,99,108,105,100,101,97,110,100,105,115,116,0, -103,112,95,101,114,97,115,101,114,0,103,112,95,115,101,116,116,105,110,103,115,0,116,98,95,108,101,102,116,109,111,117, -115,101,0,116,98,95,114,105,103,104,116,109,111,117,115,101,0,108,105,103,104,116,91,51,93,0,116,119,95,104,111,116, -115,112,111,116,0,116,119,95,102,108,97,103,0,116,119,95,104,97,110,100,108,101,115,105,122,101,0,116,119,95,115,105, -122,101,0,116,101,120,116,105,109,101,111,117,116,0,116,101,120,99,111,108,108,101,99,116,114,97,116,101,0,109,101,109, -99,97,99,104,101,108,105,109,105,116,0,112,114,101,102,101,116,99,104,102,114,97,109,101,115,0,102,114,97,109,101,115, -101,114,118,101,114,112,111,114,116,0,112,97,100,95,114,111,116,95,97,110,103,108,101,0,111,98,99,101,110,116,101,114, -95,100,105,97,0,114,118,105,115,105,122,101,0,114,118,105,98,114,105,103,104,116,0,114,101,99,101,110,116,95,102,105, -108,101,115,0,115,109,111,111,116,104,95,118,105,101,119,116,120,0,103,108,114,101,115,108,105,109,105,116,0,110,100,111, -102,95,112,97,110,0,110,100,111,102,95,114,111,116,97,116,101,0,99,117,114,115,115,105,122,101,0,112,97,100,91,56, -93,0,118,101,114,115,101,109,97,115,116,101,114,91,49,54,48,93,0,118,101,114,115,101,117,115,101,114,91,49,54,48, -93,0,103,108,97,108,112,104,97,99,108,105,112,0,97,117,116,111,107,101,121,95,102,108,97,103,0,99,111,98,97,95, -119,101,105,103,104,116,0,118,101,114,116,98,97,115,101,0,101,100,103,101,98,97,115,101,0,97,114,101,97,98,97,115, -101,0,42,115,99,101,110,101,0,101,110,100,120,0,101,110,100,121,0,115,105,122,101,120,0,115,105,122,101,121,0,115, -99,101,110,101,110,114,0,115,99,114,101,101,110,110,114,0,102,117,108,108,0,109,97,105,110,119,105,110,0,119,105,110, -97,107,116,0,104,97,110,100,108,101,114,91,56,93,0,42,110,101,119,118,0,118,101,99,0,42,118,49,0,42,118,50, -0,112,97,110,101,108,110,97,109,101,91,54,52,93,0,116,97,98,110,97,109,101,91,54,52,93,0,100,114,97,119,110, -97,109,101,91,54,52,93,0,111,102,115,120,0,111,102,115,121,0,99,111,110,116,114,111,108,0,115,110,97,112,0,111, -108,100,95,111,102,115,120,0,111,108,100,95,111,102,115,121,0,115,111,114,116,99,111,117,110,116,101,114,0,42,112,97, -110,101,108,116,97,98,0,42,118,51,0,42,118,52,0,42,102,117,108,108,0,119,105,110,109,97,116,91,52,93,91,52, -93,0,104,101,97,100,114,99,116,0,119,105,110,114,99,116,0,104,101,97,100,119,105,110,0,119,105,110,0,104,101,97, -100,101,114,116,121,112,101,0,98,117,116,115,112,97,99,101,116,121,112,101,0,119,105,110,120,0,119,105,110,121,0,104, -101,97,100,95,115,119,97,112,0,104,101,97,100,95,101,113,117,97,108,0,119,105,110,95,115,119,97,112,0,119,105,110, -95,101,113,117,97,108,0,104,101,97,100,98,117,116,108,101,110,0,104,101,97,100,98,117,116,111,102,115,0,99,117,114, -115,111,114,0,115,112,97,99,101,100,97,116,97,0,117,105,98,108,111,99,107,115,0,112,97,110,101,108,115,0,115,117, -98,118,115,116,114,91,52,93,0,115,117,98,118,101,114,115,105,111,110,0,112,97,100,115,0,109,105,110,118,101,114,115, -105,111,110,0,109,105,110,115,117,98,118,101,114,115,105,111,110,0,100,105,115,112,108,97,121,109,111,100,101,0,42,99, -117,114,115,99,114,101,101,110,0,42,99,117,114,115,99,101,110,101,0,102,105,108,101,102,108,97,103,115,0,103,108,111, -98,97,108,102,0,110,97,109,101,91,56,48,93,0,42,105,98,117,102,0,42,105,98,117,102,95,99,111,109,112,0,42, -115,101,49,0,42,115,101,50,0,42,115,101,51,0,110,114,0,98,111,116,116,111,109,0,114,105,103,104,116,0,120,111, -102,115,0,121,111,102,115,0,108,105,102,116,91,51,93,0,103,97,109,109,97,91,51,93,0,103,97,105,110,91,51,93, -0,115,97,116,117,114,97,116,105,111,110,0,42,103,117,105,0,100,105,114,91,49,54,48,93,0,100,111,110,101,0,115, -116,97,114,116,115,116,105,108,108,0,101,110,100,115,116,105,108,108,0,42,115,116,114,105,112,100,97,116,97,0,111,114, -120,0,111,114,121,0,42,99,114,111,112,0,42,116,114,97,110,115,102,111,114,109,0,42,99,111,108,111,114,95,98,97, -108,97,110,99,101,0,42,116,115,116,114,105,112,100,97,116,97,0,42,116,115,116,114,105,112,100,97,116,97,95,115,116, -97,114,116,115,116,105,108,108,0,42,116,115,116,114,105,112,100,97,116,97,95,101,110,100,115,116,105,108,108,0,42,105, -98,117,102,95,115,116,97,114,116,115,116,105,108,108,0,42,105,98,117,102,95,101,110,100,115,116,105,108,108,0,42,105, -110,115,116,97,110,99,101,95,112,114,105,118,97,116,101,95,100,97,116,97,0,42,42,99,117,114,114,101,110,116,95,112, -114,105,118,97,116,101,95,100,97,116,97,0,42,116,109,112,0,115,116,97,114,116,111,102,115,0,101,110,100,111,102,115, -0,109,97,99,104,105,110,101,0,115,116,97,114,116,100,105,115,112,0,101,110,100,100,105,115,112,0,109,117,108,0,104, -97,110,100,115,105,122,101,0,97,110,105,109,95,112,114,101,115,101,101,107,0,42,115,116,114,105,112,0,102,97,99,102, -48,0,102,97,99,102,49,0,42,115,101,113,49,0,42,115,101,113,50,0,42,115,101,113,51,0,115,101,113,98,97,115, -101,0,42,115,111,117,110,100,0,42,104,100,97,117,100,105,111,0,108,101,118,101,108,0,112,97,110,0,115,116,114,111, -98,101,0,42,101,102,102,101,99,116,100,97,116,97,0,97,110,105,109,95,115,116,97,114,116,111,102,115,0,97,110,105, -109,95,101,110,100,111,102,115,0,98,108,101,110,100,95,109,111,100,101,0,98,108,101,110,100,95,111,112,97,99,105,116, -121,0,42,111,108,100,98,97,115,101,112,0,42,112,97,114,115,101,113,0,42,115,101,113,98,97,115,101,112,0,109,101, -116,97,115,116,97,99,107,0,101,100,103,101,87,105,100,116,104,0,102,111,114,119,97,114,100,0,119,105,112,101,116,121, -112,101,0,102,77,105,110,105,0,102,67,108,97,109,112,0,102,66,111,111,115,116,0,100,68,105,115,116,0,100,81,117, -97,108,105,116,121,0,98,78,111,67,111,109,112,0,83,99,97,108,101,120,73,110,105,0,83,99,97,108,101,121,73,110, -105,0,83,99,97,108,101,120,70,105,110,0,83,99,97,108,101,121,70,105,110,0,120,73,110,105,0,120,70,105,110,0, -121,73,110,105,0,121,70,105,110,0,114,111,116,73,110,105,0,114,111,116,70,105,110,0,105,110,116,101,114,112,111,108, -97,116,105,111,110,0,42,102,114,97,109,101,77,97,112,0,103,108,111,98,97,108,83,112,101,101,100,0,108,97,115,116, -86,97,108,105,100,70,114,97,109,101,0,98,108,101,110,100,70,114,97,109,101,115,0,98,117,116,116,121,112,101,0,117, -115,101,114,106,105,116,0,115,116,97,0,116,111,116,112,97,114,116,0,110,111,114,109,102,97,99,0,111,98,102,97,99, -0,114,97,110,100,102,97,99,0,116,101,120,102,97,99,0,114,97,110,100,108,105,102,101,0,102,111,114,99,101,91,51, -93,0,118,101,99,116,115,105,122,101,0,109,97,120,108,101,110,0,100,101,102,118,101,99,91,51,93,0,109,117,108,116, -91,52,93,0,108,105,102,101,91,52,93,0,99,104,105,108,100,91,52,93,0,109,97,116,91,52,93,0,116,101,120,109, -97,112,0,99,117,114,109,117,108,116,0,115,116,97,116,105,99,115,116,101,112,0,111,109,97,116,0,116,105,109,101,116, -101,120,0,115,112,101,101,100,116,101,120,0,102,108,97,103,50,110,101,103,0,118,101,114,116,103,114,111,117,112,95,118, -0,118,103,114,111,117,112,110,97,109,101,91,51,50,93,0,118,103,114,111,117,112,110,97,109,101,95,118,91,51,50,93, -0,42,107,101,121,115,0,109,105,110,102,97,99,0,117,115,101,100,0,117,115,101,100,101,108,101,109,0,100,120,0,100, -121,0,108,105,110,107,0,111,116,121,112,101,0,111,108,100,0,42,112,111,105,110,0,42,111,108,100,112,111,105,110,0, -114,101,115,101,116,100,105,115,116,0,108,97,115,116,118,97,108,0,42,109,97,0,107,101,121,0,113,117,97,108,0,113, -117,97,108,50,0,116,97,114,103,101,116,78,97,109,101,91,51,50,93,0,116,111,103,103,108,101,78,97,109,101,91,51, -50,93,0,118,97,108,117,101,91,51,50,93,0,109,97,120,118,97,108,117,101,91,51,50,93,0,100,101,108,97,121,0, -100,117,114,97,116,105,111,110,0,109,97,116,101,114,105,97,108,78,97,109,101,91,51,50,93,0,100,97,109,112,116,105, -109,101,114,0,112,114,111,112,110,97,109,101,91,51,50,93,0,109,97,116,110,97,109,101,91,51,50,93,0,97,120,105, -115,102,108,97,103,0,42,102,114,111,109,79,98,106,101,99,116,0,115,117,98,106,101,99,116,91,51,50,93,0,98,111, -100,121,91,51,50,93,0,112,117,108,115,101,0,102,114,101,113,0,116,111,116,108,105,110,107,115,0,42,42,108,105,110, -107,115,0,116,97,112,0,106,111,121,105,110,100,101,120,0,97,120,105,115,95,115,105,110,103,108,101,0,97,120,105,115, -102,0,98,117,116,116,111,110,0,104,97,116,0,104,97,116,102,0,112,114,101,99,105,115,105,111,110,0,115,116,114,91, -49,50,56,93,0,109,111,100,117,108,101,91,54,52,93,0,42,109,121,110,101,119,0,105,110,112,117,116,115,0,116,111, -116,115,108,105,110,107,115,0,42,42,115,108,105,110,107,115,0,118,97,108,111,0,115,116,97,116,101,95,109,97,115,107, -0,42,97,99,116,0,102,114,97,109,101,80,114,111,112,91,51,50,93,0,98,108,101,110,100,105,110,0,112,114,105,111, -114,105,116,121,0,101,110,100,95,114,101,115,101,116,0,115,116,114,105,100,101,97,120,105,115,0,115,116,114,105,100,101, -108,101,110,103,116,104,0,115,110,100,110,114,0,112,97,100,49,91,50,93,0,109,97,107,101,99,111,112,121,0,99,111, -112,121,109,97,100,101,0,112,97,100,50,91,49,93,0,116,114,97,99,107,0,42,109,101,0,108,105,110,86,101,108,111, -99,105,116,121,91,51,93,0,97,110,103,86,101,108,111,99,105,116,121,91,51,93,0,108,111,99,97,108,102,108,97,103, -0,100,121,110,95,111,112,101,114,97,116,105,111,110,0,102,111,114,99,101,108,111,99,91,51,93,0,102,111,114,99,101, -114,111,116,91,51,93,0,108,105,110,101,97,114,118,101,108,111,99,105,116,121,91,51,93,0,97,110,103,117,108,97,114, -118,101,108,111,99,105,116,121,91,51,93,0,42,114,101,102,101,114,101,110,99,101,0,98,117,116,115,116,97,0,98,117, -116,101,110,100,0,109,105,110,0,109,97,120,0,118,105,115,105,102,97,99,0,114,111,116,100,97,109,112,0,109,105,110, -108,111,99,91,51,93,0,109,97,120,108,111,99,91,51,93,0,109,105,110,114,111,116,91,51,93,0,109,97,120,114,111, -116,91,51,93,0,109,97,116,112,114,111,112,91,51,50,93,0,100,105,115,116,114,105,98,117,116,105,111,110,0,105,110, -116,95,97,114,103,95,49,0,105,110,116,95,97,114,103,95,50,0,102,108,111,97,116,95,97,114,103,95,49,0,102,108, -111,97,116,95,97,114,103,95,50,0,116,111,80,114,111,112,78,97,109,101,91,51,50,93,0,42,116,111,79,98,106,101, -99,116,0,98,111,100,121,84,121,112,101,0,102,105,108,101,110,97,109,101,91,54,52,93,0,108,111,97,100,97,110,105, -110,97,109,101,91,54,52,93,0,105,110,116,95,97,114,103,0,102,108,111,97,116,95,97,114,103,0,103,111,0,97,99, -99,101,108,108,101,114,97,116,105,111,110,0,109,97,120,115,112,101,101,100,0,109,97,120,114,111,116,115,112,101,101,100, -0,109,97,120,116,105,108,116,115,112,101,101,100,0,116,105,108,116,100,97,109,112,0,115,112,101,101,100,100,97,109,112, -0,42,115,97,109,112,108,101,0,42,115,116,114,101,97,109,0,42,110,101,119,112,97,99,107,101,100,102,105,108,101,0, -42,115,110,100,95,115,111,117,110,100,0,112,97,110,110,105,110,103,0,97,116,116,101,110,117,97,116,105,111,110,0,112, -105,116,99,104,0,109,105,110,95,103,97,105,110,0,109,97,120,95,103,97,105,110,0,100,105,115,116,97,110,99,101,0, -115,116,114,101,97,109,108,101,110,0,99,104,97,110,110,101,108,115,0,104,105,103,104,112,114,105,111,0,112,97,100,91, -49,48,93,0,103,97,105,110,0,100,111,112,112,108,101,114,102,97,99,116,111,114,0,100,111,112,112,108,101,114,118,101, -108,111,99,105,116,121,0,110,117,109,115,111,117,110,100,115,98,108,101,110,100,101,114,0,110,117,109,115,111,117,110,100, -115,103,97,109,101,101,110,103,105,110,101,0,42,108,97,109,112,114,101,110,0,103,111,98,106,101,99,116,0,100,117,112, -108,105,95,111,102,115,91,51,93,0,99,104,105,108,100,98,97,115,101,0,114,111,108,108,0,104,101,97,100,91,51,93, -0,116,97,105,108,91,51,93,0,98,111,110,101,95,109,97,116,91,51,93,91,51,93,0,97,114,109,95,104,101,97,100, -91,51,93,0,97,114,109,95,116,97,105,108,91,51,93,0,97,114,109,95,109,97,116,91,52,93,91,52,93,0,120,119, -105,100,116,104,0,122,119,105,100,116,104,0,101,97,115,101,49,0,101,97,115,101,50,0,114,97,100,95,104,101,97,100, -0,114,97,100,95,116,97,105,108,0,98,111,110,101,98,97,115,101,0,99,104,97,105,110,98,97,115,101,0,112,97,116, -104,102,108,97,103,0,108,97,121,101,114,95,112,114,111,116,101,99,116,101,100,0,103,104,111,115,116,101,112,0,103,104, -111,115,116,115,105,122,101,0,103,104,111,115,116,116,121,112,101,0,112,97,116,104,115,105,122,101,0,103,104,111,115,116, -115,102,0,103,104,111,115,116,101,102,0,112,97,116,104,115,102,0,112,97,116,104,101,102,0,112,97,116,104,98,99,0, -112,97,116,104,97,99,0,99,111,110,115,116,102,108,97,103,0,105,107,102,108,97,103,0,115,101,108,101,99,116,102,108, -97,103,0,97,103,114,112,95,105,110,100,101,120,0,42,98,111,110,101,0,42,99,104,105,108,100,0,105,107,116,114,101, -101,0,42,98,95,98,111,110,101,95,109,97,116,115,0,42,100,117,97,108,95,113,117,97,116,0,42,98,95,98,111,110, -101,95,100,117,97,108,95,113,117,97,116,115,0,99,104,97,110,95,109,97,116,91,52,93,91,52,93,0,112,111,115,101, -95,109,97,116,91,52,93,91,52,93,0,112,111,115,101,95,104,101,97,100,91,51,93,0,112,111,115,101,95,116,97,105, -108,91,51,93,0,108,105,109,105,116,109,105,110,91,51,93,0,108,105,109,105,116,109,97,120,91,51,93,0,115,116,105, -102,102,110,101,115,115,91,51,93,0,105,107,115,116,114,101,116,99,104,0,42,99,117,115,116,111,109,0,99,104,97,110, -98,97,115,101,0,112,114,111,120,121,95,108,97,121,101,114,0,115,116,114,105,100,101,95,111,102,102,115,101,116,91,51, -93,0,99,121,99,108,105,99,95,111,102,102,115,101,116,91,51,93,0,97,103,114,111,117,112,115,0,97,99,116,105,118, -101,95,103,114,111,117,112,0,99,117,115,116,111,109,67,111,108,0,99,115,0,42,103,114,112,0,114,101,115,101,114,118, -101,100,49,0,103,114,111,117,112,115,0,97,99,116,105,118,101,95,109,97,114,107,101,114,0,97,99,116,110,114,0,97, -99,116,119,105,100,116,104,0,116,105,109,101,115,108,105,100,101,0,110,97,109,101,91,51,48,93,0,111,119,110,115,112, -97,99,101,0,116,97,114,115,112,97,99,101,0,101,110,102,111,114,99,101,0,104,101,97,100,116,97,105,108,0,42,116, -97,114,0,115,117,98,116,97,114,103,101,116,91,51,50,93,0,109,97,116,114,105,120,91,52,93,91,52,93,0,115,112, -97,99,101,0,42,112,114,111,112,0,116,97,114,110,117,109,0,116,97,114,103,101,116,115,0,105,116,101,114,97,116,105, -111,110,115,0,114,111,111,116,98,111,110,101,0,109,97,120,95,114,111,111,116,98,111,110,101,0,42,112,111,108,101,116, -97,114,0,112,111,108,101,115,117,98,116,97,114,103,101,116,91,51,50,93,0,112,111,108,101,97,110,103,108,101,0,111, -114,105,101,110,116,119,101,105,103,104,116,0,103,114,97,98,116,97,114,103,101,116,91,51,93,0,114,101,115,101,114,118, -101,100,50,0,109,105,110,109,97,120,102,108,97,103,0,115,116,117,99,107,0,99,97,99,104,101,91,51,93,0,108,111, -99,107,102,108,97,103,0,102,111,108,108,111,119,102,108,97,103,0,118,111,108,109,111,100,101,0,112,108,97,110,101,0, -111,114,103,108,101,110,103,116,104,0,98,117,108,103,101,0,112,105,118,88,0,112,105,118,89,0,112,105,118,90,0,97, -120,88,0,97,120,89,0,97,120,90,0,109,105,110,76,105,109,105,116,91,54,93,0,109,97,120,76,105,109,105,116,91, -54,93,0,101,120,116,114,97,70,122,0,105,110,118,109,97,116,91,52,93,91,52,93,0,102,114,111,109,0,116,111,0, -109,97,112,91,51,93,0,101,120,112,111,0,102,114,111,109,95,109,105,110,91,51,93,0,102,114,111,109,95,109,97,120, -91,51,93,0,116,111,95,109,105,110,91,51,93,0,116,111,95,109,97,120,91,51,93,0,122,109,105,110,0,122,109,97, -120,0,112,97,100,91,57,93,0,99,104,97,110,110,101,108,91,51,50,93,0,110,111,95,114,111,116,95,97,120,105,115, -0,115,116,114,105,100,101,95,97,120,105,115,0,99,117,114,109,111,100,0,97,99,116,115,116,97,114,116,0,97,99,116, -101,110,100,0,97,99,116,111,102,102,115,0,115,116,114,105,100,101,108,101,110,0,98,108,101,110,100,111,117,116,0,115, -116,114,105,100,101,99,104,97,110,110,101,108,91,51,50,93,0,111,102,102,115,95,98,111,110,101,91,51,50,93,0,104, -97,115,105,110,112,117,116,0,104,97,115,111,117,116,112,117,116,0,100,97,116,97,116,121,112,101,0,115,111,99,107,101, -116,116,121,112,101,0,42,110,101,119,95,115,111,99,107,0,110,115,0,108,105,109,105,116,0,115,116,97,99,107,95,105, -110,100,101,120,0,105,110,116,101,114,110,0,115,116,97,99,107,95,105,110,100,101,120,95,101,120,116,0,108,111,99,120, -0,108,111,99,121,0,111,119,110,95,105,110,100,101,120,0,116,111,95,105,110,100,101,120,0,42,116,111,115,111,99,107, -0,42,108,105,110,107,0,42,110,101,119,95,110,111,100,101,0,117,115,101,114,110,97,109,101,91,51,50,93,0,108,97, -115,116,121,0,111,117,116,112,117,116,115,0,42,115,116,111,114,97,103,101,0,109,105,110,105,119,105,100,116,104,0,99, -117,115,116,111,109,49,0,99,117,115,116,111,109,50,0,99,117,115,116,111,109,51,0,99,117,115,116,111,109,52,0,110, -101,101,100,95,101,120,101,99,0,101,120,101,99,0,116,111,116,114,0,98,117,116,114,0,112,114,118,114,0,42,116,121, -112,101,105,110,102,111,0,42,102,114,111,109,110,111,100,101,0,42,116,111,110,111,100,101,0,42,102,114,111,109,115,111, -99,107,0,110,111,100,101,115,0,108,105,110,107,115,0,42,115,116,97,99,107,0,42,116,104,114,101,97,100,115,116,97, -99,107,0,105,110,105,116,0,115,116,97,99,107,115,105,122,101,0,99,117,114,95,105,110,100,101,120,0,97,108,108,116, -121,112,101,115,0,42,111,119,110,116,121,112,101,0,42,115,101,108,105,110,0,42,115,101,108,111,117,116,0,40,42,116, -105,109,101,99,117,114,115,111,114,41,40,41,0,40,42,115,116,97,116,115,95,100,114,97,119,41,40,41,0,40,42,116, -101,115,116,95,98,114,101,97,107,41,40,41,0,99,121,99,108,105,99,0,109,111,118,105,101,0,115,97,109,112,108,101, -115,0,109,105,110,115,112,101,101,100,0,112,101,114,99,101,110,116,120,0,112,101,114,99,101,110,116,121,0,98,111,107, -101,104,0,99,117,114,118,101,100,0,105,109,97,103,101,95,105,110,95,119,105,100,116,104,0,105,109,97,103,101,95,105, -110,95,104,101,105,103,104,116,0,99,101,110,116,101,114,95,120,0,99,101,110,116,101,114,95,121,0,115,112,105,110,0, -105,116,101,114,0,119,114,97,112,0,115,105,103,109,97,95,99,111,108,111,114,0,115,105,103,109,97,95,115,112,97,99, -101,0,104,117,101,0,115,97,116,0,116,49,0,116,50,0,116,51,0,102,115,116,114,101,110,103,116,104,0,102,97,108, -112,104,97,0,107,101,121,91,52,93,0,120,49,0,120,50,0,121,49,0,121,50,0,99,111,108,110,97,109,101,91,51, -50,93,0,98,107,116,121,112,101,0,114,111,116,97,116,105,111,110,0,112,114,101,118,105,101,119,0,103,97,109,99,111, -0,110,111,95,122,98,117,102,0,102,115,116,111,112,0,109,97,120,98,108,117,114,0,98,116,104,114,101,115,104,0,42, -100,105,99,116,0,42,110,111,100,101,0,97,110,103,108,101,95,111,102,115,0,99,111,108,109,111,100,0,109,105,120,0, -116,104,114,101,115,104,111,108,100,0,102,97,100,101,0,109,0,99,0,106,105,116,0,112,114,111,106,0,102,105,116,0, -115,104,111,114,116,121,0,109,105,110,116,97,98,108,101,0,109,97,120,116,97,98,108,101,0,101,120,116,95,105,110,91, -50,93,0,101,120,116,95,111,117,116,91,50,93,0,42,99,117,114,118,101,0,42,116,97,98,108,101,0,42,112,114,101, -109,117,108,116,97,98,108,101,0,99,117,114,114,0,99,108,105,112,114,0,99,109,91,52,93,0,98,108,97,99,107,91, -51,93,0,119,104,105,116,101,91,51,93,0,98,119,109,117,108,91,51,93,0,115,97,109,112,108,101,91,51,93,0,111, -102,102,115,101,116,91,50,93,0,105,110,110,101,114,114,97,100,105,117,115,0,114,97,116,101,0,114,103,98,91,51,93, -0,99,108,111,110,101,0,97,99,116,105,118,101,95,114,110,100,0,97,99,116,105,118,101,95,99,108,111,110,101,0,97, -99,116,105,118,101,95,109,97,115,107,0,42,108,97,121,101,114,115,0,116,111,116,108,97,121,101,114,0,109,97,120,108, -97,121,101,114,0,116,111,116,115,105,122,101,0,42,112,111,111,108,0,101,100,105,116,102,108,97,103,0,118,101,108,91, -51,93,0,114,111,116,91,52,93,0,97,118,101,91,51,93,0,110,117,109,0,112,97,114,101,110,116,0,112,97,91,52, -93,0,119,91,52,93,0,102,117,118,91,52,93,0,102,111,102,102,115,101,116,0,114,97,110,100,91,51,93,0,42,115, -116,105,99,107,95,111,98,0,112,114,101,118,95,115,116,97,116,101,0,42,104,97,105,114,0,105,95,114,111,116,91,52, -93,0,114,95,114,111,116,91,52,93,0,114,95,97,118,101,91,51,93,0,114,95,118,101,91,51,93,0,100,105,101,116, -105,109,101,0,98,97,110,107,0,115,105,122,101,109,117,108,0,110,117,109,95,100,109,99,97,99,104,101,0,98,112,105, -0,97,108,105,118,101,0,108,111,111,112,0,100,105,115,116,114,0,112,104,121,115,116,121,112,101,0,114,111,116,109,111, -100,101,0,97,118,101,109,111,100,101,0,114,101,97,99,116,101,118,101,110,116,0,100,114,97,119,0,100,114,97,119,95, -97,115,0,100,114,97,119,95,115,105,122,101,0,99,104,105,108,100,116,121,112,101,0,100,114,97,119,95,115,116,101,112, -0,114,101,110,95,115,116,101,112,0,104,97,105,114,95,115,116,101,112,0,107,101,121,115,95,115,116,101,112,0,97,100, -97,112,116,95,97,110,103,108,101,0,97,100,97,112,116,95,112,105,120,0,114,111,116,102,114,111,109,0,105,110,116,101, -103,114,97,116,111,114,0,110,98,101,116,119,101,101,110,0,98,111,105,100,110,101,105,103,104,98,111,117,114,115,0,98, -98,95,97,108,105,103,110,0,98,98,95,117,118,95,115,112,108,105,116,0,98,98,95,97,110,105,109,0,98,98,95,115, -112,108,105,116,95,111,102,102,115,101,116,0,98,98,95,116,105,108,116,0,98,98,95,114,97,110,100,95,116,105,108,116, -0,98,98,95,111,102,102,115,101,116,91,50,93,0,115,105,109,112,108,105,102,121,95,102,108,97,103,0,115,105,109,112, -108,105,102,121,95,114,101,102,115,105,122,101,0,115,105,109,112,108,105,102,121,95,114,97,116,101,0,115,105,109,112,108, -105,102,121,95,116,114,97,110,115,105,116,105,111,110,0,115,105,109,112,108,105,102,121,95,118,105,101,119,112,111,114,116, -0,116,105,109,101,116,119,101,97,107,0,106,105,116,102,97,99,0,107,101,121,101,100,95,116,105,109,101,0,101,102,102, -95,104,97,105,114,0,103,114,105,100,95,114,101,115,0,112,97,114,116,102,97,99,0,116,97,110,102,97,99,0,116,97, -110,112,104,97,115,101,0,114,101,97,99,116,102,97,99,0,97,118,101,102,97,99,0,112,104,97,115,101,102,97,99,0, -114,97,110,100,114,111,116,102,97,99,0,114,97,110,100,112,104,97,115,101,102,97,99,0,114,97,110,100,115,105,122,101, -0,114,101,97,99,116,115,104,97,112,101,0,97,99,99,91,51,93,0,100,114,97,103,102,97,99,0,98,114,111,119,110, -102,97,99,0,100,97,109,112,102,97,99,0,97,98,115,108,101,110,103,116,104,0,114,97,110,100,108,101,110,103,116,104, -0,99,104,105,108,100,95,110,98,114,0,114,101,110,95,99,104,105,108,100,95,110,98,114,0,112,97,114,101,110,116,115, -0,99,104,105,108,100,115,105,122,101,0,99,104,105,108,100,114,97,110,100,115,105,122,101,0,99,104,105,108,100,114,97, -100,0,99,104,105,108,100,102,108,97,116,0,99,104,105,108,100,115,112,114,101,97,100,0,99,108,117,109,112,102,97,99, -0,99,108,117,109,112,112,111,119,0,114,111,117,103,104,49,0,114,111,117,103,104,49,95,115,105,122,101,0,114,111,117, -103,104,50,0,114,111,117,103,104,50,95,115,105,122,101,0,114,111,117,103,104,50,95,116,104,114,101,115,0,114,111,117, -103,104,95,101,110,100,0,114,111,117,103,104,95,101,110,100,95,115,104,97,112,101,0,98,114,97,110,99,104,95,116,104, -114,101,115,0,100,114,97,119,95,108,105,110,101,91,50,93,0,109,97,120,95,108,97,116,95,97,99,99,0,109,97,120, -95,116,97,110,95,97,99,99,0,97,118,101,114,97,103,101,95,118,101,108,0,98,97,110,107,105,110,103,0,109,97,120, -95,98,97,110,107,0,103,114,111,117,110,100,122,0,98,111,105,100,102,97,99,91,56,93,0,98,111,105,100,114,117,108, -101,91,56,93,0,42,101,102,102,95,103,114,111,117,112,0,42,100,117,112,95,111,98,0,42,98,98,95,111,98,0,42, -112,100,50,0,42,112,97,114,116,0,42,101,100,105,116,0,42,42,112,97,116,104,99,97,99,104,101,0,42,42,99,104, -105,108,100,99,97,99,104,101,0,112,97,116,104,99,97,99,104,101,98,117,102,115,0,99,104,105,108,100,99,97,99,104, -101,98,117,102,115,0,42,116,97,114,103,101,116,95,111,98,0,42,107,101,121,101,100,95,111,98,0,42,108,97,116,116, -105,99,101,0,101,102,102,101,99,116,111,114,115,0,114,101,97,99,116,101,118,101,110,116,115,0,116,111,116,99,104,105, -108,100,0,116,111,116,99,97,99,104,101,100,0,116,111,116,99,104,105,108,100,99,97,99,104,101,0,116,97,114,103,101, -116,95,112,115,121,115,0,107,101,121,101,100,95,112,115,121,115,0,116,111,116,107,101,121,101,100,0,98,97,107,101,115, -112,97,99,101,0,98,98,95,117,118,110,97,109,101,91,51,93,91,51,50,93,0,118,103,114,111,117,112,91,49,50,93, -0,118,103,95,110,101,103,0,114,116,51,0,42,114,101,110,100,101,114,100,97,116,97,0,42,99,97,99,104,101,0,67, -100,105,115,0,67,118,105,0,91,51,93,0,115,116,114,117,99,116,117,114,97,108,0,98,101,110,100,105,110,103,0,109, -97,120,95,98,101,110,100,0,109,97,120,95,115,116,114,117,99,116,0,109,97,120,95,115,104,101,97,114,0,97,118,103, -95,115,112,114,105,110,103,95,108,101,110,0,116,105,109,101,115,99,97,108,101,0,101,102,102,95,102,111,114,99,101,95, -115,99,97,108,101,0,101,102,102,95,119,105,110,100,95,115,99,97,108,101,0,115,105,109,95,116,105,109,101,95,111,108, -100,0,115,116,101,112,115,80,101,114,70,114,97,109,101,0,112,114,101,114,111,108,108,0,109,97,120,115,112,114,105,110, -103,108,101,110,0,115,111,108,118,101,114,95,116,121,112,101,0,118,103,114,111,117,112,95,98,101,110,100,0,118,103,114, -111,117,112,95,109,97,115,115,0,118,103,114,111,117,112,95,115,116,114,117,99,116,0,112,114,101,115,101,116,115,0,42, -99,111,108,108,105,115,105,111,110,95,108,105,115,116,0,101,112,115,105,108,111,110,0,115,101,108,102,95,102,114,105,99, -116,105,111,110,0,115,101,108,102,101,112,115,105,108,111,110,0,115,101,108,102,95,108,111,111,112,95,99,111,117,110,116, -0,108,111,111,112,95,99,111,117,110,116,0,112,114,101,115,115,117,114,101,0,42,112,111,105,110,116,115,0,116,111,116, -112,111,105,110,116,115,0,116,104,105,99,107,110,101,115,115,0,115,116,114,111,107,101,115,0,102,114,97,109,101,110,117, -109,0,42,97,99,116,102,114,97,109,101,0,103,115,116,101,112,0,105,110,102,111,91,49,50,56,93,0,115,98,117,102, -102,101,114,95,115,105,122,101,0,115,98,117,102,102,101,114,95,115,102,108,97,103,0,42,115,98,117,102,102,101,114,0, -0,0,0,84,89,80,69,100,1,0,0,99,104,97,114,0,117,99,104,97,114,0,115,104,111,114,116,0,117,115,104,111, -114,116,0,105,110,116,0,108,111,110,103,0,117,108,111,110,103,0,102,108,111,97,116,0,100,111,117,98,108,101,0,118, -111,105,100,0,76,105,110,107,0,76,105,110,107,68,97,116,97,0,76,105,115,116,66,97,115,101,0,118,101,99,50,115, -0,118,101,99,50,105,0,118,101,99,50,102,0,118,101,99,50,100,0,118,101,99,51,105,0,118,101,99,51,102,0,118, -101,99,51,100,0,118,101,99,52,105,0,118,101,99,52,102,0,118,101,99,52,100,0,114,99,116,105,0,114,99,116,102, -0,73,68,80,114,111,112,101,114,116,121,68,97,116,97,0,73,68,80,114,111,112,101,114,116,121,0,73,68,0,76,105, -98,114,97,114,121,0,70,105,108,101,68,97,116,97,0,80,114,101,118,105,101,119,73,109,97,103,101,0,73,112,111,68, -114,105,118,101,114,0,79,98,106,101,99,116,0,73,112,111,67,117,114,118,101,0,66,80,111,105,110,116,0,66,101,122, -84,114,105,112,108,101,0,73,112,111,0,75,101,121,66,108,111,99,107,0,75,101,121,0,83,99,114,105,112,116,76,105, -110,107,0,84,101,120,116,76,105,110,101,0,84,101,120,116,77,97,114,107,101,114,0,84,101,120,116,0,80,97,99,107, -101,100,70,105,108,101,0,67,97,109,101,114,97,0,73,109,97,103,101,85,115,101,114,0,73,109,97,103,101,0,71,80, -85,84,101,120,116,117,114,101,0,97,110,105,109,0,82,101,110,100,101,114,82,101,115,117,108,116,0,77,84,101,120,0, -84,101,120,0,80,108,117,103,105,110,84,101,120,0,67,66,68,97,116,97,0,67,111,108,111,114,66,97,110,100,0,69, -110,118,77,97,112,0,73,109,66,117,102,0,98,78,111,100,101,84,114,101,101,0,84,101,120,77,97,112,112,105,110,103, -0,76,97,109,112,0,67,117,114,118,101,77,97,112,112,105,110,103,0,87,97,118,101,0,77,97,116,101,114,105,97,108, -0,71,114,111,117,112,0,86,70,111,110,116,0,86,70,111,110,116,68,97,116,97,0,77,101,116,97,69,108,101,109,0, -66,111,117,110,100,66,111,120,0,77,101,116,97,66,97,108,108,0,78,117,114,98,0,67,104,97,114,73,110,102,111,0, -84,101,120,116,66,111,120,0,67,117,114,118,101,0,80,97,116,104,0,77,101,115,104,0,77,70,97,99,101,0,77,84, -70,97,99,101,0,84,70,97,99,101,0,77,86,101,114,116,0,77,69,100,103,101,0,77,68,101,102,111,114,109,86,101, -114,116,0,77,67,111,108,0,77,83,116,105,99,107,121,0,77,83,101,108,101,99,116,0,67,117,115,116,111,109,68,97, -116,97,0,77,117,108,116,105,114,101,115,0,80,97,114,116,105,97,108,86,105,115,105,98,105,108,105,116,121,0,77,68, -101,102,111,114,109,87,101,105,103,104,116,0,77,84,101,120,80,111,108,121,0,77,76,111,111,112,85,86,0,77,76,111, -111,112,67,111,108,0,77,70,108,111,97,116,80,114,111,112,101,114,116,121,0,77,73,110,116,80,114,111,112,101,114,116, -121,0,77,83,116,114,105,110,103,80,114,111,112,101,114,116,121,0,79,114,105,103,83,112,97,99,101,70,97,99,101,0, -77,117,108,116,105,114,101,115,67,111,108,0,77,117,108,116,105,114,101,115,67,111,108,70,97,99,101,0,77,117,108,116, -105,114,101,115,70,97,99,101,0,77,117,108,116,105,114,101,115,69,100,103,101,0,77,117,108,116,105,114,101,115,76,101, -118,101,108,0,77,117,108,116,105,114,101,115,77,97,112,78,111,100,101,0,77,111,100,105,102,105,101,114,68,97,116,97, -0,83,117,98,115,117,114,102,77,111,100,105,102,105,101,114,68,97,116,97,0,76,97,116,116,105,99,101,77,111,100,105, -102,105,101,114,68,97,116,97,0,67,117,114,118,101,77,111,100,105,102,105,101,114,68,97,116,97,0,66,117,105,108,100, -77,111,100,105,102,105,101,114,68,97,116,97,0,77,97,115,107,77,111,100,105,102,105,101,114,68,97,116,97,0,65,114, -114,97,121,77,111,100,105,102,105,101,114,68,97,116,97,0,77,105,114,114,111,114,77,111,100,105,102,105,101,114,68,97, -116,97,0,69,100,103,101,83,112,108,105,116,77,111,100,105,102,105,101,114,68,97,116,97,0,66,101,118,101,108,77,111, -100,105,102,105,101,114,68,97,116,97,0,66,77,101,115,104,77,111,100,105,102,105,101,114,68,97,116,97,0,68,105,115, -112,108,97,99,101,77,111,100,105,102,105,101,114,68,97,116,97,0,85,86,80,114,111,106,101,99,116,77,111,100,105,102, -105,101,114,68,97,116,97,0,68,101,99,105,109,97,116,101,77,111,100,105,102,105,101,114,68,97,116,97,0,83,109,111, -111,116,104,77,111,100,105,102,105,101,114,68,97,116,97,0,67,97,115,116,77,111,100,105,102,105,101,114,68,97,116,97, -0,87,97,118,101,77,111,100,105,102,105,101,114,68,97,116,97,0,65,114,109,97,116,117,114,101,77,111,100,105,102,105, -101,114,68,97,116,97,0,72,111,111,107,77,111,100,105,102,105,101,114,68,97,116,97,0,83,111,102,116,98,111,100,121, -77,111,100,105,102,105,101,114,68,97,116,97,0,67,108,111,116,104,77,111,100,105,102,105,101,114,68,97,116,97,0,67, -108,111,116,104,0,67,108,111,116,104,83,105,109,83,101,116,116,105,110,103,115,0,67,108,111,116,104,67,111,108,108,83, -101,116,116,105,110,103,115,0,80,111,105,110,116,67,97,99,104,101,0,67,111,108,108,105,115,105,111,110,77,111,100,105, -102,105,101,114,68,97,116,97,0,66,86,72,84,114,101,101,0,83,117,114,102,97,99,101,77,111,100,105,102,105,101,114, -68,97,116,97,0,68,101,114,105,118,101,100,77,101,115,104,0,66,86,72,84,114,101,101,70,114,111,109,77,101,115,104, -0,66,111,111,108,101,97,110,77,111,100,105,102,105,101,114,68,97,116,97,0,77,68,101,102,73,110,102,108,117,101,110, -99,101,0,77,68,101,102,67,101,108,108,0,77,101,115,104,68,101,102,111,114,109,77,111,100,105,102,105,101,114,68,97, -116,97,0,80,97,114,116,105,99,108,101,83,121,115,116,101,109,77,111,100,105,102,105,101,114,68,97,116,97,0,80,97, -114,116,105,99,108,101,83,121,115,116,101,109,0,80,97,114,116,105,99,108,101,73,110,115,116,97,110,99,101,77,111,100, -105,102,105,101,114,68,97,116,97,0,69,120,112,108,111,100,101,77,111,100,105,102,105,101,114,68,97,116,97,0,70,108, -117,105,100,115,105,109,77,111,100,105,102,105,101,114,68,97,116,97,0,70,108,117,105,100,115,105,109,83,101,116,116,105, -110,103,115,0,83,104,114,105,110,107,119,114,97,112,77,111,100,105,102,105,101,114,68,97,116,97,0,83,105,109,112,108, -101,68,101,102,111,114,109,77,111,100,105,102,105,101,114,68,97,116,97,0,76,97,116,116,105,99,101,0,98,68,101,102, -111,114,109,71,114,111,117,112,0,98,65,99,116,105,111,110,0,98,80,111,115,101,0,66,117,108,108,101,116,83,111,102, -116,66,111,100,121,0,80,97,114,116,68,101,102,108,101,99,116,0,83,111,102,116,66,111,100,121,0,79,98,72,111,111, -107,0,82,78,71,0,83,66,86,101,114,116,101,120,0,66,111,100,121,80,111,105,110,116,0,66,111,100,121,83,112,114, -105,110,103,0,83,66,83,99,114,97,116,99,104,0,87,111,114,108,100,0,82,97,100,105,111,0,66,97,115,101,0,65, -118,105,67,111,100,101,99,68,97,116,97,0,81,117,105,99,107,116,105,109,101,67,111,100,101,99,68,97,116,97,0,70, -70,77,112,101,103,67,111,100,101,99,68,97,116,97,0,65,117,100,105,111,68,97,116,97,0,83,99,101,110,101,82,101, -110,100,101,114,76,97,121,101,114,0,82,101,110,100,101,114,68,97,116,97,0,82,101,110,100,101,114,80,114,111,102,105, -108,101,0,71,97,109,101,70,114,97,109,105,110,103,0,84,105,109,101,77,97,114,107,101,114,0,73,109,97,103,101,80, -97,105,110,116,83,101,116,116,105,110,103,115,0,66,114,117,115,104,0,80,97,114,116,105,99,108,101,66,114,117,115,104, -68,97,116,97,0,80,97,114,116,105,99,108,101,69,100,105,116,83,101,116,116,105,110,103,115,0,84,114,97,110,115,102, -111,114,109,79,114,105,101,110,116,97,116,105,111,110,0,84,111,111,108,83,101,116,116,105,110,103,115,0,66,114,117,115, -104,68,97,116,97,0,83,99,117,108,112,116,68,97,116,97,0,83,99,117,108,112,116,83,101,115,115,105,111,110,0,83, -99,101,110,101,0,68,97,103,70,111,114,101,115,116,0,66,71,112,105,99,0,86,105,101,119,51,68,0,83,112,97,99, -101,76,105,110,107,0,83,99,114,65,114,101,97,0,82,101,110,100,101,114,73,110,102,111,0,82,101,116,111,112,111,86, -105,101,119,68,97,116,97,0,86,105,101,119,68,101,112,116,104,115,0,98,71,80,100,97,116,97,0,86,105,101,119,50, -68,0,83,112,97,99,101,73,110,102,111,0,83,112,97,99,101,73,112,111,0,83,112,97,99,101,66,117,116,115,0,83, -112,97,99,101,83,101,113,0,83,112,97,99,101,70,105,108,101,0,100,105,114,101,110,116,114,121,0,66,108,101,110,100, -72,97,110,100,108,101,0,83,112,97,99,101,79,111,112,115,0,84,114,101,101,83,116,111,114,101,0,84,114,101,101,83, -116,111,114,101,69,108,101,109,0,83,112,97,99,101,73,109,97,103,101,0,83,112,97,99,101,78,108,97,0,83,112,97, -99,101,84,101,120,116,0,83,99,114,105,112,116,0,83,112,97,99,101,83,99,114,105,112,116,0,83,112,97,99,101,84, -105,109,101,0,83,112,97,99,101,78,111,100,101,0,83,112,97,99,101,73,109,97,83,101,108,0,70,105,108,101,76,105, -115,116,0,84,104,101,109,101,85,73,0,84,104,101,109,101,83,112,97,99,101,0,84,104,101,109,101,87,105,114,101,67, -111,108,111,114,0,98,84,104,101,109,101,0,83,111,108,105,100,76,105,103,104,116,0,85,115,101,114,68,101,102,0,98, -83,99,114,101,101,110,0,83,99,114,86,101,114,116,0,83,99,114,69,100,103,101,0,80,97,110,101,108,0,70,105,108, -101,71,108,111,98,97,108,0,83,116,114,105,112,69,108,101,109,0,84,83,116,114,105,112,69,108,101,109,0,83,116,114, -105,112,67,114,111,112,0,83,116,114,105,112,84,114,97,110,115,102,111,114,109,0,83,116,114,105,112,67,111,108,111,114, -66,97,108,97,110,99,101,0,83,116,114,105,112,67,111,108,111,114,66,97,108,97,110,99,101,71,85,73,72,101,108,112, -101,114,0,83,116,114,105,112,80,114,111,120,121,0,83,116,114,105,112,0,80,108,117,103,105,110,83,101,113,0,83,101, -113,117,101,110,99,101,0,98,83,111,117,110,100,0,104,100,97,117,100,105,111,0,77,101,116,97,83,116,97,99,107,0, -69,100,105,116,105,110,103,0,87,105,112,101,86,97,114,115,0,71,108,111,119,86,97,114,115,0,84,114,97,110,115,102, -111,114,109,86,97,114,115,0,83,111,108,105,100,67,111,108,111,114,86,97,114,115,0,83,112,101,101,100,67,111,110,116, -114,111,108,86,97,114,115,0,69,102,102,101,99,116,0,66,117,105,108,100,69,102,102,0,80,97,114,116,69,102,102,0, -80,97,114,116,105,99,108,101,0,87,97,118,101,69,102,102,0,79,111,112,115,0,98,80,114,111,112,101,114,116,121,0, -98,78,101,97,114,83,101,110,115,111,114,0,98,77,111,117,115,101,83,101,110,115,111,114,0,98,84,111,117,99,104,83, -101,110,115,111,114,0,98,75,101,121,98,111,97,114,100,83,101,110,115,111,114,0,98,80,114,111,112,101,114,116,121,83, -101,110,115,111,114,0,98,65,99,116,117,97,116,111,114,83,101,110,115,111,114,0,98,68,101,108,97,121,83,101,110,115, -111,114,0,98,67,111,108,108,105,115,105,111,110,83,101,110,115,111,114,0,98,82,97,100,97,114,83,101,110,115,111,114, -0,98,82,97,110,100,111,109,83,101,110,115,111,114,0,98,82,97,121,83,101,110,115,111,114,0,98,77,101,115,115,97, -103,101,83,101,110,115,111,114,0,98,83,101,110,115,111,114,0,98,67,111,110,116,114,111,108,108,101,114,0,98,74,111, -121,115,116,105,99,107,83,101,110,115,111,114,0,98,69,120,112,114,101,115,115,105,111,110,67,111,110,116,0,98,80,121, -116,104,111,110,67,111,110,116,0,98,65,99,116,117,97,116,111,114,0,98,65,100,100,79,98,106,101,99,116,65,99,116, -117,97,116,111,114,0,98,65,99,116,105,111,110,65,99,116,117,97,116,111,114,0,98,83,111,117,110,100,65,99,116,117, -97,116,111,114,0,98,67,68,65,99,116,117,97,116,111,114,0,98,69,100,105,116,79,98,106,101,99,116,65,99,116,117, -97,116,111,114,0,98,83,99,101,110,101,65,99,116,117,97,116,111,114,0,98,80,114,111,112,101,114,116,121,65,99,116, -117,97,116,111,114,0,98,79,98,106,101,99,116,65,99,116,117,97,116,111,114,0,98,73,112,111,65,99,116,117,97,116, -111,114,0,98,67,97,109,101,114,97,65,99,116,117,97,116,111,114,0,98,67,111,110,115,116,114,97,105,110,116,65,99, -116,117,97,116,111,114,0,98,71,114,111,117,112,65,99,116,117,97,116,111,114,0,98,82,97,110,100,111,109,65,99,116, -117,97,116,111,114,0,98,77,101,115,115,97,103,101,65,99,116,117,97,116,111,114,0,98,71,97,109,101,65,99,116,117, -97,116,111,114,0,98,86,105,115,105,98,105,108,105,116,121,65,99,116,117,97,116,111,114,0,98,84,119,111,68,70,105, -108,116,101,114,65,99,116,117,97,116,111,114,0,98,80,97,114,101,110,116,65,99,116,117,97,116,111,114,0,98,83,116, -97,116,101,65,99,116,117,97,116,111,114,0,70,114,101,101,67,97,109,101,114,97,0,98,83,97,109,112,108,101,0,98, -83,111,117,110,100,76,105,115,116,101,110,101,114,0,83,112,97,99,101,83,111,117,110,100,0,71,114,111,117,112,79,98, -106,101,99,116,0,66,111,110,101,0,98,65,114,109,97,116,117,114,101,0,98,80,111,115,101,67,104,97,110,110,101,108, -0,98,65,99,116,105,111,110,71,114,111,117,112,0,98,65,99,116,105,111,110,67,104,97,110,110,101,108,0,83,112,97, -99,101,65,99,116,105,111,110,0,98,67,111,110,115,116,114,97,105,110,116,67,104,97,110,110,101,108,0,98,67,111,110, -115,116,114,97,105,110,116,0,98,67,111,110,115,116,114,97,105,110,116,84,97,114,103,101,116,0,98,80,121,116,104,111, -110,67,111,110,115,116,114,97,105,110,116,0,98,75,105,110,101,109,97,116,105,99,67,111,110,115,116,114,97,105,110,116, -0,98,84,114,97,99,107,84,111,67,111,110,115,116,114,97,105,110,116,0,98,82,111,116,97,116,101,76,105,107,101,67, -111,110,115,116,114,97,105,110,116,0,98,76,111,99,97,116,101,76,105,107,101,67,111,110,115,116,114,97,105,110,116,0, -98,77,105,110,77,97,120,67,111,110,115,116,114,97,105,110,116,0,98,83,105,122,101,76,105,107,101,67,111,110,115,116, -114,97,105,110,116,0,98,65,99,116,105,111,110,67,111,110,115,116,114,97,105,110,116,0,98,76,111,99,107,84,114,97, -99,107,67,111,110,115,116,114,97,105,110,116,0,98,70,111,108,108,111,119,80,97,116,104,67,111,110,115,116,114,97,105, -110,116,0,98,83,116,114,101,116,99,104,84,111,67,111,110,115,116,114,97,105,110,116,0,98,82,105,103,105,100,66,111, -100,121,74,111,105,110,116,67,111,110,115,116,114,97,105,110,116,0,98,67,108,97,109,112,84,111,67,111,110,115,116,114, -97,105,110,116,0,98,67,104,105,108,100,79,102,67,111,110,115,116,114,97,105,110,116,0,98,84,114,97,110,115,102,111, -114,109,67,111,110,115,116,114,97,105,110,116,0,98,76,111,99,76,105,109,105,116,67,111,110,115,116,114,97,105,110,116, -0,98,82,111,116,76,105,109,105,116,67,111,110,115,116,114,97,105,110,116,0,98,83,105,122,101,76,105,109,105,116,67, -111,110,115,116,114,97,105,110,116,0,98,68,105,115,116,76,105,109,105,116,67,111,110,115,116,114,97,105,110,116,0,98, -83,104,114,105,110,107,119,114,97,112,67,111,110,115,116,114,97,105,110,116,0,98,65,99,116,105,111,110,77,111,100,105, -102,105,101,114,0,98,65,99,116,105,111,110,83,116,114,105,112,0,98,78,111,100,101,83,116,97,99,107,0,98,78,111, -100,101,83,111,99,107,101,116,0,98,78,111,100,101,76,105,110,107,0,98,78,111,100,101,0,98,78,111,100,101,80,114, -101,118,105,101,119,0,98,78,111,100,101,84,121,112,101,0,78,111,100,101,73,109,97,103,101,65,110,105,109,0,78,111, -100,101,66,108,117,114,68,97,116,97,0,78,111,100,101,68,66,108,117,114,68,97,116,97,0,78,111,100,101,66,105,108, -97,116,101,114,97,108,66,108,117,114,68,97,116,97,0,78,111,100,101,72,117,101,83,97,116,0,78,111,100,101,73,109, -97,103,101,70,105,108,101,0,78,111,100,101,67,104,114,111,109,97,0,78,111,100,101,84,119,111,88,89,115,0,78,111, -100,101,84,119,111,70,108,111,97,116,115,0,78,111,100,101,71,101,111,109,101,116,114,121,0,78,111,100,101,86,101,114, -116,101,120,67,111,108,0,78,111,100,101,68,101,102,111,99,117,115,0,78,111,100,101,83,99,114,105,112,116,68,105,99, -116,0,78,111,100,101,71,108,97,114,101,0,78,111,100,101,84,111,110,101,109,97,112,0,78,111,100,101,76,101,110,115, -68,105,115,116,0,84,101,120,78,111,100,101,79,117,116,112,117,116,0,67,117,114,118,101,77,97,112,80,111,105,110,116, -0,67,117,114,118,101,77,97,112,0,66,114,117,115,104,67,108,111,110,101,0,67,117,115,116,111,109,68,97,116,97,76, -97,121,101,114,0,72,97,105,114,75,101,121,0,80,97,114,116,105,99,108,101,75,101,121,0,67,104,105,108,100,80,97, -114,116,105,99,108,101,0,80,97,114,116,105,99,108,101,68,97,116,97,0,80,97,114,116,105,99,108,101,83,101,116,116, -105,110,103,115,0,80,97,114,116,105,99,108,101,69,100,105,116,0,80,97,114,116,105,99,108,101,67,97,99,104,101,75, -101,121,0,76,105,110,107,78,111,100,101,0,98,71,80,68,115,112,111,105,110,116,0,98,71,80,68,115,116,114,111,107, -101,0,98,71,80,68,102,114,97,109,101,0,98,71,80,68,108,97,121,101,114,0,0,84,76,69,78,1,0,1,0,2, -0,2,0,4,0,4,0,4,0,4,0,8,0,0,0,8,0,12,0,8,0,4,0,8,0,8,0,16,0,12,0,12, -0,24,0,16,0,16,0,32,0,16,0,16,0,20,0,76,0,52,0,40,2,0,0,32,0,-116,0,80,3,92,0,36, -0,56,0,84,0,112,0,120,0,16,0,24,0,40,0,120,0,20,0,-124,0,32,0,-128,1,0,0,0,0,0,0,-120, -0,16,1,84,1,24,0,8,3,-88,0,0,0,124,0,-124,0,-128,1,8,1,56,0,108,2,76,0,68,1,0,0,108, -0,104,0,-120,0,56,0,8,0,16,0,56,1,0,0,24,1,20,0,44,0,60,0,24,0,12,0,12,0,4,0,8, -0,8,0,24,0,76,0,32,0,8,0,12,0,8,0,8,0,4,0,4,0,0,1,32,0,16,0,64,0,24,0,12, -0,56,0,0,0,52,0,68,0,88,0,96,0,68,0,96,0,116,0,64,0,60,0,108,0,60,0,-108,0,-104,0,60, -0,92,0,104,0,-72,0,100,0,-76,0,52,0,68,0,0,0,-124,0,28,0,20,0,100,0,0,0,60,0,0,0,0, -0,64,0,8,0,8,0,-40,0,76,0,64,1,64,0,64,0,60,0,-92,1,108,0,104,0,116,0,40,0,84,0,56, -0,120,0,-128,0,-8,0,-48,0,0,0,16,0,0,0,0,0,0,0,108,1,40,0,28,0,-80,0,-112,0,52,0,16, -0,72,0,-48,3,56,0,16,0,80,0,12,0,-72,0,8,0,72,0,80,0,-24,0,8,0,-88,0,0,0,124,5,0, -0,60,0,28,3,36,0,-52,0,0,0,0,0,0,0,20,0,-120,0,36,0,88,1,-36,0,-56,0,-56,1,0,0,0, -0,8,1,12,0,12,0,8,1,-76,0,-128,0,80,2,36,0,-92,0,-36,0,-124,2,0,0,-104,0,-48,0,16,0,56, -14,56,0,32,12,120,0,20,0,24,0,-28,0,32,0,80,0,28,0,16,0,8,0,60,0,0,0,-4,0,-16,0,-88, -1,-60,0,28,1,0,0,16,0,28,0,12,0,24,0,48,0,16,0,28,0,16,0,24,0,56,1,0,0,56,0,44, -0,64,0,48,0,8,0,44,0,72,0,104,0,40,0,8,0,72,0,44,0,40,0,108,0,68,0,76,0,80,0,60, -0,-128,0,76,0,60,0,12,0,92,0,28,0,20,0,80,0,16,0,76,0,108,0,84,0,28,0,96,0,60,0,56, -0,108,0,-116,0,4,0,20,0,12,0,8,0,40,0,0,0,68,0,-80,0,24,0,4,1,116,0,-104,1,72,0,64, -0,-64,0,44,0,64,0,116,0,60,0,104,0,52,0,44,0,44,0,68,0,44,0,64,0,44,0,20,0,52,0,96, -0,12,0,108,0,92,0,28,0,28,0,28,0,52,0,20,0,60,0,-116,0,36,0,120,0,24,0,-52,0,0,0,0, -0,16,0,40,0,28,0,12,0,12,0,16,1,40,0,8,0,8,0,64,0,32,0,24,0,8,0,24,0,32,0,8, -0,32,0,12,0,44,0,20,0,68,0,24,0,56,0,72,0,-4,0,-32,1,0,0,0,0,0,0,16,0,20,0,24, -0,-84,0,83,84,82,67,57,1,0,0,10,0,2,0,10,0,0,0,10,0,1,0,11,0,3,0,11,0,0,0,11, -0,1,0,9,0,2,0,12,0,2,0,9,0,3,0,9,0,4,0,13,0,2,0,2,0,5,0,2,0,6,0,14, -0,2,0,4,0,5,0,4,0,6,0,15,0,2,0,7,0,5,0,7,0,6,0,16,0,2,0,8,0,5,0,8, -0,6,0,17,0,3,0,4,0,5,0,4,0,6,0,4,0,7,0,18,0,3,0,7,0,5,0,7,0,6,0,7, -0,7,0,19,0,3,0,8,0,5,0,8,0,6,0,8,0,7,0,20,0,4,0,4,0,5,0,4,0,6,0,4, -0,7,0,4,0,8,0,21,0,4,0,7,0,5,0,7,0,6,0,7,0,7,0,7,0,8,0,22,0,4,0,8, -0,5,0,8,0,6,0,8,0,7,0,8,0,8,0,23,0,4,0,4,0,9,0,4,0,10,0,4,0,11,0,4, -0,12,0,24,0,4,0,7,0,9,0,7,0,10,0,7,0,11,0,7,0,12,0,25,0,4,0,9,0,13,0,12, -0,14,0,4,0,15,0,4,0,16,0,26,0,10,0,26,0,0,0,26,0,1,0,0,0,17,0,0,0,18,0,0, -0,19,0,2,0,20,0,4,0,21,0,25,0,22,0,4,0,23,0,4,0,24,0,27,0,9,0,9,0,0,0,9, -0,1,0,27,0,25,0,28,0,26,0,0,0,27,0,2,0,28,0,2,0,20,0,4,0,29,0,26,0,30,0,28, -0,8,0,27,0,31,0,27,0,32,0,29,0,33,0,0,0,34,0,0,0,35,0,4,0,36,0,4,0,37,0,28, -0,38,0,30,0,6,0,4,0,39,0,4,0,40,0,2,0,41,0,2,0,42,0,2,0,43,0,4,0,44,0,31, -0,6,0,32,0,45,0,2,0,46,0,2,0,47,0,2,0,18,0,2,0,20,0,0,0,48,0,33,0,21,0,33, -0,0,0,33,0,1,0,34,0,49,0,35,0,50,0,24,0,51,0,24,0,52,0,2,0,46,0,2,0,47,0,2, -0,53,0,2,0,54,0,2,0,55,0,2,0,56,0,2,0,20,0,2,0,57,0,7,0,11,0,7,0,12,0,4, -0,58,0,7,0,59,0,7,0,60,0,7,0,61,0,31,0,62,0,36,0,7,0,27,0,31,0,12,0,63,0,24, -0,64,0,2,0,46,0,2,0,65,0,2,0,66,0,2,0,37,0,37,0,16,0,37,0,0,0,37,0,1,0,7, -0,67,0,7,0,61,0,2,0,18,0,2,0,47,0,2,0,68,0,2,0,20,0,4,0,69,0,4,0,70,0,9, -0,2,0,7,0,71,0,0,0,17,0,0,0,72,0,7,0,73,0,7,0,74,0,38,0,12,0,27,0,31,0,37, -0,75,0,0,0,76,0,4,0,77,0,7,0,61,0,12,0,78,0,36,0,79,0,27,0,80,0,2,0,18,0,2, -0,81,0,2,0,82,0,2,0,20,0,39,0,5,0,27,0,83,0,2,0,84,0,2,0,85,0,2,0,86,0,4, -0,37,0,40,0,6,0,40,0,0,0,40,0,1,0,0,0,87,0,0,0,88,0,4,0,23,0,4,0,89,0,41, -0,10,0,41,0,0,0,41,0,1,0,4,0,90,0,4,0,91,0,4,0,92,0,4,0,43,0,4,0,14,0,4, -0,93,0,0,0,94,0,0,0,95,0,42,0,15,0,27,0,31,0,0,0,96,0,4,0,93,0,4,0,97,0,12, -0,98,0,40,0,99,0,40,0,100,0,4,0,101,0,4,0,102,0,12,0,103,0,0,0,104,0,4,0,105,0,4, -0,106,0,9,0,107,0,8,0,108,0,43,0,5,0,4,0,109,0,4,0,110,0,4,0,93,0,4,0,37,0,9, -0,2,0,44,0,20,0,27,0,31,0,2,0,18,0,2,0,20,0,7,0,111,0,7,0,112,0,7,0,113,0,7, -0,114,0,7,0,115,0,7,0,116,0,7,0,117,0,7,0,118,0,7,0,119,0,7,0,120,0,7,0,121,0,2, -0,122,0,2,0,123,0,7,0,124,0,36,0,79,0,39,0,125,0,32,0,126,0,45,0,12,0,4,0,127,0,4, -0,-128,0,4,0,-127,0,4,0,-126,0,2,0,-125,0,2,0,-124,0,2,0,20,0,2,0,-123,0,2,0,-122,0,2, -0,-121,0,2,0,-120,0,2,0,-119,0,46,0,32,0,27,0,31,0,0,0,34,0,12,0,-118,0,47,0,-117,0,48, -0,-116,0,49,0,-115,0,2,0,-123,0,2,0,20,0,2,0,-114,0,2,0,18,0,2,0,37,0,2,0,43,0,4, -0,-113,0,2,0,-112,0,2,0,-111,0,2,0,-110,0,2,0,-109,0,2,0,-108,0,2,0,-107,0,4,0,-106,0,4, -0,-105,0,43,0,-104,0,30,0,-103,0,7,0,-102,0,4,0,-101,0,2,0,-100,0,2,0,-99,0,2,0,-98,0,2, -0,-97,0,7,0,-96,0,7,0,-95,0,9,0,-94,0,50,0,31,0,2,0,-93,0,2,0,-92,0,2,0,-91,0,2, -0,-90,0,32,0,-89,0,51,0,-88,0,0,0,-87,0,0,0,-86,0,0,0,-85,0,0,0,-84,0,0,0,-83,0,7, -0,-82,0,7,0,-81,0,2,0,-80,0,2,0,-79,0,2,0,-78,0,2,0,-77,0,2,0,-76,0,2,0,-75,0,2, -0,-74,0,7,0,-73,0,7,0,-72,0,7,0,-71,0,7,0,-70,0,7,0,-69,0,7,0,57,0,7,0,-68,0,7, -0,-67,0,7,0,-66,0,7,0,-65,0,7,0,-64,0,52,0,15,0,0,0,-63,0,9,0,-62,0,0,0,-61,0,0, -0,-60,0,4,0,-59,0,4,0,-58,0,9,0,-57,0,7,0,-56,0,7,0,-55,0,7,0,-54,0,4,0,-53,0,9, -0,-52,0,9,0,-51,0,4,0,-50,0,4,0,37,0,53,0,6,0,7,0,-73,0,7,0,-72,0,7,0,-71,0,7, -0,-49,0,7,0,67,0,4,0,64,0,54,0,5,0,2,0,20,0,2,0,36,0,2,0,64,0,2,0,-48,0,53, -0,-54,0,55,0,17,0,32,0,-89,0,46,0,-47,0,56,0,-46,0,7,0,-45,0,7,0,-44,0,2,0,18,0,2, -0,-43,0,7,0,113,0,7,0,114,0,7,0,-42,0,4,0,-41,0,2,0,-40,0,2,0,-39,0,4,0,-123,0,4, -0,-113,0,2,0,-38,0,2,0,-37,0,51,0,56,0,27,0,31,0,7,0,-36,0,7,0,-35,0,7,0,-34,0,7, -0,-33,0,7,0,-32,0,7,0,-31,0,7,0,-30,0,7,0,-29,0,7,0,-28,0,7,0,-27,0,7,0,-26,0,7, -0,-25,0,7,0,-24,0,7,0,-23,0,7,0,-22,0,7,0,-21,0,7,0,-20,0,7,0,-19,0,7,0,-18,0,7, -0,-17,0,2,0,-16,0,2,0,-15,0,2,0,-14,0,2,0,-13,0,2,0,-12,0,2,0,-11,0,2,0,-10,0,2, -0,20,0,2,0,18,0,2,0,-43,0,7,0,-9,0,7,0,-8,0,7,0,-7,0,7,0,-6,0,2,0,-5,0,2, -0,-4,0,2,0,-3,0,2,0,-125,0,4,0,23,0,4,0,-128,0,4,0,-127,0,4,0,-126,0,7,0,-2,0,7, -0,-1,0,7,0,-67,0,45,0,0,1,57,0,1,1,36,0,79,0,46,0,-47,0,52,0,2,1,54,0,3,1,55, -0,4,1,30,0,-103,0,0,0,5,1,0,0,6,1,58,0,8,0,7,0,7,1,7,0,8,1,7,0,-81,0,4, -0,20,0,7,0,9,1,7,0,10,1,7,0,11,1,32,0,45,0,59,0,80,0,27,0,31,0,2,0,18,0,2, -0,12,1,4,0,13,1,2,0,-79,0,2,0,14,1,7,0,-73,0,7,0,-72,0,7,0,-71,0,7,0,-70,0,7, -0,15,1,7,0,16,1,7,0,17,1,7,0,18,1,7,0,19,1,7,0,20,1,7,0,21,1,7,0,22,1,7, -0,23,1,7,0,24,1,7,0,25,1,60,0,26,1,2,0,27,1,2,0,70,0,7,0,113,0,7,0,114,0,7, -0,28,1,7,0,29,1,7,0,30,1,2,0,31,1,2,0,32,1,2,0,33,1,2,0,34,1,0,0,35,1,0, -0,36,1,2,0,37,1,2,0,38,1,2,0,39,1,2,0,40,1,2,0,41,1,7,0,42,1,7,0,43,1,7, -0,44,1,7,0,45,1,2,0,46,1,2,0,43,0,2,0,47,1,2,0,48,1,2,0,49,1,2,0,50,1,7, -0,51,1,7,0,52,1,7,0,53,1,7,0,54,1,7,0,55,1,7,0,56,1,7,0,57,1,7,0,58,1,7, -0,59,1,7,0,60,1,7,0,61,1,7,0,62,1,2,0,63,1,2,0,64,1,4,0,65,1,4,0,66,1,2, -0,67,1,2,0,68,1,2,0,69,1,2,0,70,1,7,0,71,1,7,0,72,1,7,0,73,1,7,0,74,1,2, -0,75,1,2,0,76,1,50,0,77,1,36,0,79,0,30,0,-103,0,39,0,125,0,61,0,2,0,27,0,31,0,36, -0,79,0,62,0,-127,0,27,0,31,0,2,0,-79,0,2,0,20,0,7,0,-73,0,7,0,-72,0,7,0,-71,0,7, -0,78,1,7,0,79,1,7,0,80,1,7,0,81,1,7,0,82,1,7,0,83,1,7,0,84,1,7,0,85,1,7, -0,86,1,7,0,87,1,7,0,88,1,7,0,89,1,7,0,90,1,7,0,91,1,7,0,92,1,7,0,93,1,7, -0,94,1,7,0,95,1,7,0,96,1,7,0,97,1,7,0,98,1,7,0,99,1,7,0,100,1,7,0,101,1,7, -0,102,1,7,0,103,1,7,0,104,1,2,0,105,1,2,0,106,1,2,0,107,1,0,0,108,1,0,0,109,1,7, -0,110,1,7,0,111,1,2,0,112,1,2,0,113,1,7,0,114,1,7,0,115,1,7,0,116,1,7,0,117,1,2, -0,118,1,2,0,119,1,4,0,13,1,4,0,120,1,2,0,121,1,2,0,122,1,2,0,123,1,2,0,124,1,7, -0,125,1,7,0,126,1,7,0,127,1,7,0,-128,1,7,0,-127,1,7,0,-126,1,7,0,-125,1,7,0,-124,1,7, -0,-123,1,7,0,-122,1,0,0,-121,1,7,0,-120,1,7,0,-119,1,7,0,-118,1,4,0,-117,1,0,0,-116,1,0, -0,47,1,0,0,-115,1,0,0,5,1,2,0,-114,1,2,0,-113,1,2,0,64,1,2,0,-112,1,2,0,-111,1,2, -0,-110,1,7,0,-109,1,7,0,-108,1,7,0,-107,1,7,0,-106,1,7,0,-105,1,2,0,-93,0,2,0,-92,0,54, -0,-104,1,54,0,-103,1,0,0,-102,1,0,0,-101,1,0,0,-100,1,0,0,-99,1,2,0,-98,1,2,0,12,1,7, -0,-97,1,7,0,-96,1,50,0,77,1,57,0,1,1,36,0,79,0,63,0,-95,1,30,0,-103,0,7,0,-94,1,7, -0,-93,1,7,0,-92,1,7,0,-91,1,7,0,-90,1,2,0,-89,1,2,0,70,0,7,0,-88,1,7,0,-87,1,7, -0,-86,1,7,0,-85,1,7,0,-84,1,7,0,-83,1,7,0,-82,1,7,0,-81,1,7,0,-80,1,2,0,-79,1,2, -0,-78,1,7,0,-77,1,7,0,-76,1,7,0,-75,1,7,0,-74,1,7,0,-73,1,4,0,-72,1,4,0,-71,1,4, -0,-70,1,39,0,125,0,12,0,-69,1,64,0,6,0,27,0,31,0,0,0,-68,1,7,0,-67,1,7,0,37,0,65, -0,2,0,43,0,-104,0,66,0,26,0,66,0,0,0,66,0,1,0,67,0,-66,1,4,0,-65,1,4,0,-64,1,4, -0,-63,1,4,0,-62,1,4,0,-61,1,4,0,-60,1,2,0,18,0,2,0,20,0,2,0,-59,1,2,0,-58,1,7, -0,5,0,7,0,6,0,7,0,7,0,7,0,-57,1,7,0,-56,1,7,0,-55,1,7,0,-54,1,7,0,-53,1,7, -0,-52,1,7,0,-51,1,7,0,23,0,7,0,-50,1,7,0,-49,1,68,0,15,0,27,0,31,0,67,0,-66,1,12, -0,-48,1,12,0,-47,1,36,0,79,0,62,0,-46,1,2,0,20,0,2,0,-45,1,4,0,-80,0,7,0,7,1,7, -0,-81,0,7,0,8,1,7,0,-44,1,7,0,-43,1,7,0,-42,1,35,0,10,0,7,0,-41,1,7,0,-40,1,7, -0,-39,1,7,0,-38,1,2,0,-37,1,2,0,-36,1,0,0,-35,1,0,0,-34,1,0,0,-33,1,0,0,-32,1,34, -0,7,0,7,0,-31,1,7,0,-40,1,7,0,-39,1,2,0,-35,1,2,0,-32,1,7,0,-38,1,7,0,37,0,69, -0,21,0,69,0,0,0,69,0,1,0,2,0,18,0,2,0,-30,1,2,0,-32,1,2,0,20,0,2,0,-29,1,2, -0,-28,1,2,0,-27,1,2,0,-26,1,2,0,-25,1,2,0,-24,1,2,0,-23,1,2,0,-22,1,7,0,-21,1,7, -0,-20,1,34,0,49,0,35,0,50,0,2,0,-19,1,2,0,-18,1,4,0,-17,1,70,0,5,0,2,0,-16,1,2, -0,-30,1,0,0,20,0,0,0,37,0,2,0,70,0,71,0,4,0,7,0,5,0,7,0,6,0,7,0,8,0,7, -0,-15,1,72,0,57,0,27,0,31,0,67,0,-66,1,12,0,-14,1,12,0,-47,1,32,0,-13,1,32,0,-12,1,32, -0,-11,1,36,0,79,0,73,0,-10,1,38,0,-9,1,62,0,-46,1,12,0,-8,1,7,0,7,1,7,0,-81,0,7, -0,8,1,4,0,-80,0,2,0,-7,1,2,0,-45,1,2,0,20,0,2,0,-6,1,7,0,-5,1,7,0,-4,1,7, -0,-3,1,2,0,-27,1,2,0,-26,1,2,0,-2,1,2,0,-1,1,4,0,70,0,2,0,23,0,2,0,98,0,2, -0,67,0,2,0,0,2,7,0,1,2,7,0,2,2,7,0,3,2,7,0,4,2,7,0,5,2,7,0,6,2,7, -0,7,2,7,0,8,2,7,0,9,2,7,0,10,2,0,0,11,2,0,0,12,2,64,0,13,2,64,0,14,2,64, -0,15,2,64,0,16,2,4,0,17,2,4,0,18,2,4,0,19,2,4,0,37,0,71,0,20,2,4,0,21,2,4, -0,22,2,70,0,23,2,70,0,24,2,74,0,39,0,27,0,31,0,67,0,-66,1,12,0,25,2,36,0,79,0,38, -0,-9,1,62,0,-46,1,75,0,26,2,76,0,27,2,77,0,28,2,78,0,29,2,79,0,30,2,80,0,31,2,81, -0,32,2,82,0,33,2,74,0,34,2,83,0,35,2,84,0,36,2,84,0,37,2,84,0,38,2,4,0,54,0,4, -0,39,2,4,0,40,2,4,0,41,2,4,0,42,2,4,0,-80,0,7,0,7,1,7,0,-81,0,7,0,8,1,7, -0,43,2,7,0,37,0,2,0,44,2,2,0,20,0,2,0,45,2,2,0,46,2,2,0,-45,1,2,0,47,2,85, -0,48,2,86,0,49,2,9,0,-94,0,77,0,8,0,9,0,50,2,7,0,51,2,4,0,52,2,0,0,20,0,0, -0,53,2,2,0,13,1,2,0,54,2,2,0,55,2,75,0,8,0,4,0,56,2,4,0,57,2,4,0,58,2,4, -0,59,2,0,0,37,0,0,0,-30,1,0,0,60,2,0,0,20,0,79,0,5,0,4,0,56,2,4,0,57,2,0, -0,61,2,0,0,62,2,2,0,20,0,87,0,2,0,4,0,63,2,7,0,-39,1,80,0,3,0,87,0,64,2,4, -0,65,2,4,0,20,0,78,0,6,0,7,0,66,2,2,0,67,2,0,0,20,0,0,0,-30,1,0,0,62,2,0, -0,68,2,81,0,4,0,0,0,-49,0,0,0,-73,0,0,0,-72,0,0,0,-71,0,88,0,6,0,46,0,50,2,0, -0,20,0,0,0,53,2,2,0,13,1,2,0,54,2,2,0,55,2,89,0,1,0,7,0,69,2,90,0,5,0,0, -0,-49,0,0,0,-73,0,0,0,-72,0,0,0,-71,0,4,0,37,0,82,0,1,0,7,0,70,2,83,0,2,0,4, -0,71,2,4,0,18,0,76,0,7,0,7,0,51,2,46,0,50,2,0,0,20,0,0,0,53,2,2,0,13,1,2, -0,54,2,2,0,55,2,91,0,1,0,7,0,72,2,92,0,1,0,4,0,73,2,93,0,1,0,0,0,74,2,94, -0,1,0,7,0,51,2,95,0,4,0,7,0,-49,0,7,0,-73,0,7,0,-72,0,7,0,-71,0,96,0,1,0,95, -0,52,2,97,0,5,0,4,0,75,2,4,0,76,2,0,0,20,0,0,0,-30,1,0,0,-74,0,98,0,2,0,4, -0,77,2,4,0,76,2,99,0,14,0,99,0,0,0,99,0,1,0,97,0,78,2,96,0,79,2,98,0,80,2,0, -0,81,2,12,0,82,2,12,0,83,2,100,0,84,2,4,0,54,0,4,0,40,2,4,0,39,2,4,0,37,0,78, -0,85,2,85,0,14,0,12,0,86,2,78,0,85,2,0,0,87,2,0,0,88,2,0,0,89,2,0,0,90,2,0, -0,91,2,0,0,92,2,0,0,93,2,0,0,20,0,84,0,36,2,84,0,38,2,2,0,94,2,0,0,95,2,86, -0,8,0,4,0,96,2,4,0,97,2,75,0,98,2,79,0,99,2,4,0,40,2,4,0,39,2,4,0,54,0,4, -0,37,0,101,0,6,0,101,0,0,0,101,0,1,0,4,0,18,0,4,0,13,1,0,0,17,0,0,0,100,2,102, -0,7,0,101,0,101,2,2,0,102,2,2,0,86,2,2,0,103,2,2,0,93,0,9,0,104,2,9,0,105,2,103, -0,3,0,101,0,101,2,32,0,-89,0,0,0,17,0,104,0,5,0,101,0,101,2,32,0,-89,0,0,0,17,0,2, -0,106,2,0,0,107,2,105,0,5,0,101,0,101,2,7,0,91,0,7,0,108,2,4,0,109,2,4,0,110,2,106, -0,5,0,101,0,101,2,32,0,111,2,0,0,72,0,4,0,13,1,4,0,20,0,107,0,13,0,101,0,101,2,32, -0,112,2,32,0,113,2,32,0,114,2,32,0,115,2,7,0,116,2,7,0,117,2,7,0,108,2,7,0,118,2,4, -0,119,2,4,0,120,2,4,0,93,0,4,0,121,2,108,0,5,0,101,0,101,2,2,0,122,2,2,0,20,0,7, -0,123,2,32,0,124,2,109,0,3,0,101,0,101,2,7,0,125,2,4,0,93,0,110,0,10,0,101,0,101,2,7, -0,126,2,4,0,127,2,4,0,37,0,2,0,93,0,2,0,-128,2,2,0,-127,2,2,0,-126,2,7,0,-125,2,0, -0,-124,2,111,0,3,0,101,0,101,2,7,0,37,0,4,0,18,0,112,0,11,0,101,0,101,2,51,0,-123,2,7, -0,-122,2,4,0,-121,2,0,0,-124,2,7,0,-120,2,4,0,-119,2,32,0,-118,2,0,0,-117,2,4,0,-116,2,4, -0,37,0,113,0,10,0,101,0,101,2,32,0,-115,2,46,0,-114,2,4,0,93,0,4,0,-113,2,7,0,-112,2,7, -0,-111,2,0,0,-117,2,4,0,-116,2,4,0,37,0,114,0,3,0,101,0,101,2,7,0,-110,2,4,0,-109,2,115, -0,5,0,101,0,101,2,7,0,-108,2,0,0,-124,2,2,0,20,0,2,0,-107,2,116,0,8,0,101,0,101,2,32, -0,-89,0,7,0,-108,2,7,0,-38,1,7,0,109,0,0,0,-124,2,2,0,20,0,2,0,18,0,117,0,21,0,101, -0,101,2,32,0,-106,2,0,0,-124,2,51,0,-123,2,32,0,-118,2,2,0,20,0,2,0,37,0,7,0,-105,2,7, -0,-104,2,7,0,-103,2,7,0,-5,1,7,0,-102,2,7,0,-101,2,7,0,-100,2,7,0,-99,2,4,0,-119,2,4, -0,-116,2,0,0,-117,2,7,0,-98,2,7,0,-97,2,7,0,43,0,118,0,7,0,101,0,101,2,2,0,-96,2,2, -0,-95,2,4,0,70,0,32,0,-89,0,7,0,-94,2,0,0,-124,2,119,0,9,0,101,0,101,2,32,0,-89,0,7, -0,-93,2,7,0,-92,2,7,0,-99,2,4,0,-91,2,4,0,-90,2,7,0,-89,2,0,0,17,0,120,0,1,0,101, -0,101,2,121,0,5,0,101,0,101,2,122,0,-88,2,123,0,-87,2,124,0,-86,2,125,0,-85,2,126,0,14,0,101, -0,101,2,78,0,-84,2,78,0,-83,2,78,0,-82,2,78,0,-81,2,78,0,-80,2,78,0,-79,2,75,0,-78,2,4, -0,-77,2,4,0,-76,2,2,0,-75,2,2,0,37,0,7,0,-74,2,127,0,-73,2,-128,0,3,0,101,0,101,2,-127, -0,-72,2,-126,0,-73,2,-125,0,4,0,101,0,101,2,32,0,-89,0,4,0,-71,2,4,0,37,0,-124,0,2,0,4, -0,-70,2,7,0,-39,1,-123,0,2,0,4,0,-127,0,4,0,-69,2,-122,0,20,0,101,0,101,2,32,0,-89,0,0, -0,-124,2,2,0,-68,2,2,0,-67,2,2,0,20,0,2,0,37,0,7,0,-66,2,7,0,-65,2,4,0,54,0,4, -0,-64,2,-123,0,-63,2,-124,0,-62,2,4,0,-61,2,4,0,-60,2,4,0,-59,2,4,0,-69,2,7,0,-58,2,7, -0,-57,2,7,0,-56,2,-121,0,8,0,101,0,101,2,-120,0,-55,2,-127,0,-72,2,4,0,-54,2,4,0,-53,2,4, -0,-52,2,2,0,20,0,2,0,57,0,-119,0,5,0,101,0,101,2,32,0,45,0,2,0,-51,2,2,0,20,0,2, -0,-50,2,-118,0,5,0,101,0,101,2,4,0,-49,2,2,0,20,0,2,0,-48,2,7,0,-47,2,-117,0,3,0,101, -0,101,2,-116,0,-46,2,125,0,-85,2,-115,0,10,0,101,0,101,2,32,0,-45,2,32,0,-44,2,0,0,-43,2,7, -0,-42,2,2,0,-41,2,2,0,-40,2,0,0,-39,2,0,0,-38,2,0,0,107,2,-114,0,9,0,101,0,101,2,32, -0,-37,2,0,0,-43,2,7,0,-36,2,7,0,-35,2,0,0,13,1,0,0,122,2,0,0,-34,2,0,0,37,0,-113, -0,24,0,27,0,31,0,2,0,-29,1,2,0,-28,1,2,0,-33,2,2,0,20,0,2,0,-32,2,2,0,-31,2,2, -0,-30,2,2,0,70,0,0,0,-29,2,0,0,-28,2,0,0,-27,2,0,0,18,0,4,0,37,0,7,0,-26,2,7, -0,-25,2,7,0,-24,2,7,0,-23,2,7,0,-22,2,7,0,-21,2,34,0,-20,2,36,0,79,0,38,0,-9,1,80, -0,31,2,-112,0,3,0,-112,0,0,0,-112,0,1,0,0,0,17,0,67,0,3,0,7,0,-19,2,4,0,20,0,4, -0,37,0,32,0,111,0,27,0,31,0,2,0,18,0,2,0,-18,2,4,0,-17,2,4,0,-16,2,4,0,-15,2,0, -0,-14,2,32,0,38,0,32,0,-13,2,32,0,-12,2,32,0,-11,2,32,0,-10,2,36,0,79,0,73,0,-10,1,67, -0,-66,1,-111,0,-9,2,-111,0,-8,2,-110,0,-7,2,9,0,2,0,12,0,-6,2,12,0,25,2,12,0,-47,1,12, -0,-5,2,12,0,-4,2,62,0,-46,1,7,0,7,1,7,0,-3,2,7,0,-2,2,7,0,-81,0,7,0,-1,2,7, -0,8,1,7,0,0,3,7,0,1,3,7,0,-93,2,7,0,2,3,7,0,-45,0,4,0,3,3,2,0,20,0,2, -0,4,3,2,0,5,3,2,0,6,3,2,0,7,3,2,0,8,3,2,0,9,3,2,0,10,3,2,0,11,3,2, -0,12,3,2,0,13,3,2,0,14,3,4,0,15,3,4,0,16,3,4,0,17,3,4,0,18,3,7,0,19,3,7, -0,20,3,7,0,21,3,7,0,22,3,7,0,23,3,7,0,24,3,7,0,25,3,7,0,26,3,7,0,27,3,7, -0,28,3,7,0,29,3,7,0,30,3,0,0,31,3,0,0,32,3,0,0,-45,1,0,0,33,3,0,0,34,3,0, -0,35,3,7,0,36,3,7,0,37,3,39,0,125,0,12,0,38,3,12,0,39,3,12,0,40,3,12,0,41,3,7, -0,42,3,2,0,71,2,2,0,43,3,7,0,52,2,4,0,44,3,4,0,45,3,-109,0,46,3,2,0,47,3,2, -0,-38,0,7,0,48,3,12,0,49,3,12,0,50,3,12,0,51,3,12,0,52,3,-108,0,53,3,-107,0,54,3,63, -0,55,3,2,0,56,3,2,0,57,3,2,0,58,3,2,0,59,3,7,0,44,2,2,0,60,3,2,0,61,3,-116, -0,62,3,-127,0,63,3,-127,0,64,3,4,0,65,3,4,0,66,3,4,0,67,3,4,0,70,0,9,0,-94,0,12, -0,68,3,-106,0,14,0,-106,0,0,0,-106,0,1,0,32,0,38,0,7,0,-93,2,7,0,9,1,7,0,-92,2,7, -0,-99,2,0,0,17,0,4,0,-91,2,4,0,-90,2,4,0,69,3,2,0,18,0,2,0,70,3,7,0,-89,2,-108, -0,36,0,2,0,71,3,2,0,72,3,2,0,20,0,2,0,-99,2,7,0,73,3,7,0,74,3,7,0,75,3,7, -0,76,3,7,0,77,3,7,0,78,3,7,0,79,3,7,0,80,3,7,0,81,3,7,0,82,3,7,0,83,3,7, -0,84,3,7,0,85,3,7,0,86,3,7,0,87,3,7,0,88,3,7,0,89,3,7,0,90,3,7,0,91,3,7, -0,92,3,7,0,93,3,7,0,94,3,7,0,95,3,7,0,96,3,2,0,97,3,2,0,98,3,2,0,99,3,2, -0,100,3,51,0,-88,0,-105,0,101,3,7,0,102,3,4,0,110,2,125,0,5,0,4,0,20,0,4,0,103,3,4, -0,104,3,4,0,105,3,4,0,106,3,-104,0,1,0,7,0,-31,1,-109,0,30,0,4,0,20,0,7,0,107,3,7, -0,108,3,7,0,109,3,4,0,110,3,4,0,111,3,4,0,112,3,4,0,113,3,7,0,114,3,7,0,115,3,7, -0,116,3,7,0,117,3,7,0,118,3,7,0,119,3,7,0,120,3,7,0,121,3,7,0,122,3,7,0,123,3,7, -0,124,3,7,0,125,3,7,0,126,3,7,0,127,3,7,0,-128,3,7,0,-127,3,7,0,-126,3,7,0,-125,3,4, -0,-124,3,4,0,-123,3,7,0,-122,3,7,0,27,3,-107,0,49,0,-120,0,-121,3,4,0,-120,3,4,0,-119,3,-103, -0,-118,3,-102,0,-117,3,0,0,37,0,0,0,-116,3,2,0,-115,3,7,0,-114,3,0,0,-113,3,7,0,-112,3,7, -0,-111,3,7,0,-110,3,7,0,-109,3,7,0,-108,3,7,0,-107,3,7,0,-106,3,7,0,-105,3,7,0,-104,3,2, -0,-103,3,0,0,-102,3,2,0,-101,3,7,0,-100,3,7,0,-99,3,0,0,-98,3,4,0,-126,0,4,0,-97,3,4, -0,-96,3,2,0,-95,3,2,0,-94,3,-104,0,-93,3,4,0,-92,3,4,0,81,0,7,0,-91,3,7,0,-90,3,7, -0,-89,3,7,0,-88,3,2,0,-87,3,2,0,-86,3,2,0,-85,3,2,0,-84,3,2,0,-83,3,2,0,-82,3,2, -0,-81,3,2,0,-80,3,-101,0,-79,3,7,0,-78,3,7,0,-77,3,125,0,-76,3,-116,0,48,0,2,0,18,0,2, -0,-75,3,2,0,-74,3,2,0,-73,3,7,0,-72,3,2,0,-71,3,2,0,-70,3,7,0,-69,3,2,0,-68,3,2, -0,-67,3,7,0,-66,3,7,0,-65,3,7,0,-64,3,7,0,-63,3,7,0,-62,3,7,0,-61,3,4,0,-60,3,7, -0,-59,3,7,0,-58,3,7,0,-57,3,74,0,-56,3,74,0,-55,3,74,0,-54,3,0,0,-53,3,7,0,-52,3,7, -0,-51,3,36,0,79,0,2,0,-50,3,0,0,-49,3,0,0,-48,3,7,0,-47,3,4,0,-46,3,7,0,-45,3,7, -0,-44,3,4,0,-43,3,4,0,20,0,7,0,-42,3,7,0,-41,3,7,0,-40,3,78,0,-39,3,7,0,-38,3,7, -0,-37,3,7,0,-36,3,7,0,-35,3,7,0,-34,3,7,0,-33,3,7,0,-32,3,4,0,-31,3,-100,0,71,0,27, -0,31,0,2,0,-79,0,2,0,14,1,2,0,47,1,2,0,-30,3,7,0,-29,3,7,0,-28,3,7,0,-27,3,7, -0,-26,3,7,0,-25,3,7,0,-24,3,7,0,-23,3,7,0,-22,3,7,0,84,1,7,0,86,1,7,0,85,1,7, -0,-21,3,4,0,-20,3,7,0,-19,3,7,0,-18,3,7,0,-17,3,7,0,-16,3,7,0,-15,3,7,0,-14,3,7, -0,-13,3,2,0,-12,3,2,0,13,1,2,0,-11,3,2,0,-10,3,2,0,-9,3,2,0,-8,3,2,0,-7,3,2, -0,-6,3,7,0,-5,3,7,0,-4,3,7,0,-3,3,7,0,-2,3,7,0,-1,3,7,0,0,4,7,0,1,4,7, -0,2,4,7,0,3,4,7,0,4,4,7,0,5,4,7,0,6,4,2,0,7,4,2,0,8,4,2,0,9,4,2, -0,10,4,7,0,11,4,7,0,12,4,7,0,13,4,7,0,14,4,2,0,15,4,2,0,16,4,2,0,17,4,2, -0,18,4,7,0,19,4,7,0,20,4,7,0,21,4,7,0,22,4,2,0,23,4,2,0,24,4,2,0,25,4,2, -0,43,0,7,0,26,4,7,0,27,4,36,0,79,0,50,0,77,1,30,0,-103,0,39,0,125,0,-99,0,16,0,2, -0,28,4,2,0,29,4,2,0,30,4,2,0,20,0,2,0,31,4,2,0,32,4,2,0,33,4,2,0,34,4,2, -0,35,4,2,0,36,4,2,0,37,4,2,0,38,4,4,0,39,4,7,0,40,4,7,0,41,4,7,0,42,4,-98, -0,8,0,-98,0,0,0,-98,0,1,0,4,0,3,3,4,0,43,4,4,0,20,0,2,0,44,4,2,0,45,4,32, -0,-89,0,-97,0,13,0,9,0,46,4,9,0,47,4,4,0,48,4,4,0,49,4,4,0,50,4,4,0,51,4,4, -0,52,4,4,0,53,4,4,0,54,4,4,0,55,4,4,0,56,4,4,0,37,0,0,0,57,4,-96,0,5,0,9, -0,58,4,9,0,59,4,4,0,60,4,4,0,70,0,0,0,61,4,-95,0,13,0,4,0,18,0,4,0,62,4,4, -0,63,4,4,0,64,4,4,0,65,4,4,0,66,4,4,0,93,0,4,0,67,4,4,0,68,4,4,0,69,4,4, -0,70,4,4,0,71,4,26,0,30,0,-94,0,4,0,4,0,72,4,7,0,73,4,2,0,20,0,2,0,68,2,-93, -0,11,0,-93,0,0,0,-93,0,1,0,0,0,17,0,62,0,74,4,63,0,75,4,4,0,3,3,4,0,76,4,4, -0,77,4,4,0,37,0,4,0,78,4,4,0,79,4,-92,0,-126,0,-97,0,80,4,-96,0,81,4,-95,0,82,4,4, -0,83,4,4,0,-126,0,4,0,-97,3,4,0,84,4,4,0,85,4,4,0,86,4,4,0,87,4,2,0,20,0,2, -0,88,4,7,0,20,3,7,0,89,4,7,0,90,4,7,0,91,4,7,0,92,4,7,0,93,4,2,0,94,4,2, -0,95,4,2,0,96,4,2,0,97,4,2,0,-39,0,2,0,98,4,2,0,99,4,2,0,100,3,2,0,100,4,2, -0,101,4,2,0,34,1,2,0,109,0,2,0,102,4,2,0,103,4,2,0,104,4,2,0,105,4,2,0,106,4,2, -0,107,4,2,0,108,4,2,0,109,4,2,0,110,4,2,0,35,1,2,0,111,4,2,0,112,4,2,0,113,4,2, -0,114,4,4,0,115,4,4,0,13,1,2,0,116,4,2,0,117,4,2,0,118,4,2,0,119,4,2,0,120,4,2, -0,121,4,24,0,122,4,24,0,123,4,23,0,124,4,12,0,125,4,2,0,126,4,2,0,37,0,7,0,127,4,7, -0,-128,4,7,0,-127,4,7,0,-126,4,7,0,-125,4,7,0,-124,4,7,0,-123,4,7,0,-122,4,7,0,-121,4,2, -0,-120,4,2,0,-119,4,2,0,-118,4,2,0,-117,4,2,0,-116,4,2,0,-115,4,7,0,-114,4,7,0,-113,4,7, -0,-112,4,2,0,-111,4,2,0,-110,4,2,0,-109,4,2,0,-108,4,2,0,-107,4,2,0,-106,4,2,0,-105,4,2, -0,-104,4,2,0,-103,4,2,0,-102,4,4,0,-101,4,4,0,-100,4,4,0,-99,4,4,0,-98,4,4,0,-97,4,7, -0,-96,4,4,0,-95,4,4,0,-94,4,4,0,-93,4,4,0,-92,4,7,0,-91,4,7,0,-90,4,7,0,-89,4,7, -0,-88,4,7,0,-87,4,7,0,-86,4,7,0,-85,4,7,0,-84,4,7,0,-83,4,0,0,-82,4,0,0,-81,4,4, -0,-80,4,2,0,-79,4,2,0,12,1,0,0,-78,4,7,0,-77,4,7,0,-76,4,4,0,-75,4,4,0,-74,4,7, -0,-73,4,7,0,-72,4,2,0,-71,4,2,0,-70,4,7,0,-69,4,2,0,-68,4,2,0,-67,4,4,0,-66,4,2, -0,-65,4,2,0,-64,4,2,0,-63,4,2,0,-62,4,7,0,-61,4,7,0,70,0,42,0,-60,4,-91,0,9,0,-91, -0,0,0,-91,0,1,0,0,0,17,0,2,0,-59,4,2,0,-58,4,2,0,-57,4,2,0,43,0,7,0,-56,4,7, -0,70,0,-90,0,5,0,7,0,-55,4,0,0,18,0,0,0,43,0,0,0,70,0,0,0,12,1,-89,0,5,0,-89, -0,0,0,-89,0,1,0,4,0,-54,4,0,0,-53,4,4,0,20,0,-88,0,5,0,-87,0,-52,4,2,0,20,0,2, -0,-51,4,2,0,-50,4,2,0,-49,4,-86,0,4,0,2,0,109,0,2,0,-122,2,2,0,-48,4,2,0,-47,4,-85, -0,7,0,2,0,20,0,2,0,-46,4,2,0,-45,4,2,0,-44,4,-86,0,-43,4,7,0,-42,4,4,0,-41,4,-84, -0,4,0,-84,0,0,0,-84,0,1,0,0,0,-40,4,7,0,-39,4,-83,0,56,0,2,0,-38,4,2,0,-37,4,7, -0,-36,4,7,0,-35,4,2,0,-48,4,2,0,-34,4,7,0,-33,4,7,0,-32,4,2,0,-31,4,2,0,-30,4,2, -0,-29,4,2,0,-28,4,7,0,-27,4,7,0,-26,4,7,0,-25,4,7,0,37,0,2,0,-24,4,2,0,-23,4,2, -0,-22,4,2,0,-21,4,-88,0,-20,4,-85,0,-19,4,7,0,-18,4,7,0,-17,4,0,0,-16,4,0,0,-15,4,0, -0,-14,4,0,0,-13,4,0,0,-12,4,0,0,-11,4,2,0,-10,4,7,0,-9,4,7,0,-8,4,7,0,-7,4,7, -0,-6,4,7,0,-5,4,7,0,-4,4,7,0,-3,4,7,0,-2,4,7,0,-1,4,7,0,0,5,2,0,1,5,0, -0,2,5,0,0,3,5,0,0,4,5,0,0,5,5,32,0,6,5,0,0,7,5,0,0,8,5,0,0,9,5,0, -0,10,5,0,0,11,5,0,0,12,5,0,0,13,5,0,0,14,5,0,0,15,5,-82,0,6,0,2,0,109,0,0, -0,-122,2,0,0,16,5,0,0,17,5,0,0,20,0,0,0,-74,0,-81,0,26,0,-80,0,18,5,50,0,77,1,60, -0,19,5,-82,0,20,5,-82,0,21,5,-82,0,22,5,-82,0,23,5,-82,0,24,5,-82,0,25,5,-82,0,26,5,7, -0,27,5,2,0,28,5,2,0,47,1,2,0,29,5,2,0,1,2,0,0,30,5,0,0,31,5,0,0,32,5,0, -0,33,5,0,0,93,0,0,0,34,5,0,0,35,5,0,0,36,5,0,0,37,5,0,0,38,5,0,0,-74,0,-79, -0,43,0,27,0,31,0,32,0,39,5,-100,0,40,5,-79,0,41,5,46,0,-47,0,12,0,42,5,-98,0,43,5,7, -0,44,5,7,0,45,5,7,0,46,5,7,0,47,5,4,0,3,3,7,0,48,5,2,0,49,5,2,0,50,5,2, -0,51,5,2,0,52,5,2,0,53,5,2,0,54,5,2,0,55,5,2,0,5,1,57,0,1,1,9,0,56,5,-99, -0,57,5,-90,0,58,5,-83,0,59,5,-92,0,-73,0,-94,0,60,5,39,0,125,0,12,0,103,0,12,0,61,5,2, -0,62,5,2,0,63,5,2,0,64,5,2,0,65,5,-78,0,66,5,2,0,67,5,2,0,68,5,2,0,64,1,2, -0,-38,0,-81,0,69,5,4,0,70,5,4,0,37,0,-77,0,9,0,46,0,-47,0,45,0,0,1,7,0,8,2,7, -0,9,2,7,0,109,0,7,0,71,5,7,0,72,5,2,0,73,5,2,0,74,5,-76,0,75,0,-75,0,0,0,-75, -0,1,0,4,0,75,5,7,0,76,5,-74,0,77,5,2,0,78,5,7,0,79,5,7,0,80,5,7,0,81,5,7, -0,82,5,7,0,83,5,7,0,84,5,7,0,85,5,7,0,20,1,7,0,86,5,4,0,87,5,2,0,88,5,2, -0,17,5,32,0,39,5,32,0,89,5,-77,0,90,5,-76,0,91,5,-73,0,92,5,-72,0,93,5,-71,0,94,5,0, -0,95,5,2,0,30,4,2,0,96,5,4,0,3,3,4,0,97,5,2,0,98,5,2,0,99,5,2,0,100,5,0, -0,101,5,0,0,43,0,7,0,115,0,7,0,102,5,7,0,103,5,7,0,104,5,7,0,105,5,7,0,106,5,7, -0,107,5,7,0,108,5,7,0,-82,0,7,0,44,5,2,0,109,5,2,0,110,5,2,0,111,5,2,0,112,5,2, -0,-119,0,2,0,29,5,2,0,113,5,2,0,114,5,2,0,115,5,2,0,116,5,7,0,117,5,7,0,118,5,67, -0,119,5,12,0,120,5,2,0,121,5,2,0,53,2,2,0,122,5,2,0,20,0,2,0,123,5,2,0,124,5,2, -0,125,5,0,0,126,5,0,0,127,5,9,0,-128,5,-70,0,-127,5,7,0,-126,5,2,0,-125,5,2,0,-124,5,2, -0,53,5,2,0,54,5,-69,0,19,0,24,0,36,0,24,0,64,0,23,0,-123,5,23,0,-122,5,23,0,-121,5,7, -0,-120,5,7,0,-119,5,7,0,-118,5,7,0,-117,5,2,0,-116,5,2,0,-115,5,2,0,-114,5,2,0,-113,5,2, -0,-112,5,2,0,-111,5,4,0,20,0,7,0,-110,5,2,0,99,5,0,0,107,2,-75,0,6,0,-75,0,0,0,-75, -0,1,0,4,0,75,5,7,0,76,5,-74,0,77,5,2,0,78,5,-68,0,6,0,-75,0,0,0,-75,0,1,0,4, -0,75,5,7,0,76,5,-74,0,77,5,2,0,78,5,-67,0,27,0,-75,0,0,0,-75,0,1,0,4,0,75,5,7, -0,76,5,-74,0,77,5,2,0,78,5,4,0,-109,5,4,0,70,0,-69,0,-108,5,9,0,-107,5,12,0,-106,5,36, -0,79,0,27,0,80,0,0,0,-105,5,0,0,-104,5,0,0,-103,5,2,0,-102,5,2,0,-101,5,2,0,-100,5,2, -0,-99,5,2,0,65,0,2,0,46,0,2,0,-119,0,2,0,-98,5,4,0,20,0,7,0,-97,5,24,0,36,0,-66, -0,29,0,-75,0,0,0,-75,0,1,0,4,0,75,5,7,0,76,5,-74,0,77,5,-73,0,92,5,2,0,78,5,2, -0,-96,5,2,0,-95,5,2,0,-94,5,2,0,-93,5,-69,0,-108,5,2,0,-92,5,2,0,-119,0,2,0,-101,5,2, -0,-91,5,9,0,-90,5,2,0,29,5,0,0,-89,5,0,0,-88,5,2,0,-87,5,2,0,-86,5,2,0,12,3,2, -0,-85,5,2,0,-84,5,0,0,37,0,0,0,20,0,0,0,47,1,0,0,-83,5,-65,0,16,0,-75,0,0,0,-75, -0,1,0,4,0,75,5,7,0,76,5,-74,0,77,5,2,0,78,5,-69,0,-108,5,7,0,8,2,7,0,9,2,2, -0,-92,5,2,0,-82,5,2,0,-81,5,2,0,-80,5,4,0,20,0,7,0,71,5,-70,0,-127,5,-64,0,33,0,-75, -0,0,0,-75,0,1,0,4,0,75,5,7,0,76,5,-74,0,77,5,2,0,78,5,-63,0,-79,5,4,0,-78,5,0, -0,-77,5,0,0,-76,5,0,0,-75,5,2,0,18,0,2,0,-74,5,2,0,20,0,2,0,-73,5,2,0,-72,5,2, -0,-71,5,2,0,-70,5,2,0,43,0,4,0,70,0,0,0,-69,5,-62,0,-68,5,2,0,-67,5,2,0,-66,5,2, -0,-65,5,2,0,-48,0,9,0,-64,5,9,0,-63,5,9,0,-62,5,9,0,-61,5,9,0,-60,5,2,0,-59,5,0, -0,-58,5,-61,0,23,0,-75,0,0,0,-75,0,1,0,4,0,75,5,7,0,76,5,-74,0,77,5,2,0,78,5,-69, -0,-108,5,12,0,-57,5,2,0,-101,5,2,0,-56,5,2,0,20,0,2,0,57,0,9,0,-90,5,12,0,-55,5,-60, -0,-54,5,0,0,-53,5,-59,0,-52,5,4,0,-51,5,4,0,-50,5,2,0,18,0,2,0,-49,5,2,0,-48,5,2, -0,-47,5,-58,0,29,0,-75,0,0,0,-75,0,1,0,4,0,75,5,7,0,76,5,-74,0,77,5,2,0,78,5,-69, -0,-108,5,46,0,-114,2,45,0,0,1,60,0,19,5,2,0,13,1,2,0,-119,0,2,0,-46,5,2,0,-45,5,4, -0,20,0,2,0,49,5,2,0,-44,5,2,0,-98,5,2,0,-101,5,7,0,71,5,0,0,-43,5,0,0,-42,5,0, -0,-41,5,0,0,-40,5,7,0,8,2,7,0,9,2,7,0,-39,5,7,0,-38,5,-70,0,-127,5,-57,0,11,0,-75, -0,0,0,-75,0,1,0,4,0,75,5,7,0,76,5,-74,0,77,5,2,0,78,5,2,0,-119,0,2,0,-98,5,2, -0,-37,5,2,0,20,0,-69,0,-108,5,-56,0,24,0,-75,0,0,0,-75,0,1,0,4,0,75,5,7,0,76,5,-74, -0,77,5,2,0,78,5,42,0,-36,5,4,0,-35,5,4,0,-34,5,2,0,93,0,2,0,-119,0,4,0,-33,5,4, -0,-32,5,4,0,-31,5,4,0,-30,5,4,0,-29,5,4,0,-28,5,4,0,-27,5,4,0,-26,5,7,0,-25,5,23, -0,-24,5,23,0,-23,5,4,0,-22,5,4,0,-21,5,-55,0,10,0,27,0,31,0,9,0,-20,5,9,0,-19,5,9, -0,-18,5,9,0,-17,5,9,0,-16,5,4,0,93,0,4,0,-15,5,0,0,-14,5,0,0,-13,5,-54,0,10,0,-75, -0,0,0,-75,0,1,0,4,0,75,5,7,0,76,5,-74,0,77,5,-55,0,-12,5,2,0,93,0,2,0,-119,0,4, -0,43,0,9,0,-11,5,-53,0,8,0,-75,0,0,0,-75,0,1,0,4,0,75,5,7,0,76,5,-74,0,77,5,-69, -0,-108,5,4,0,20,0,4,0,-10,5,-52,0,21,0,-75,0,0,0,-75,0,1,0,4,0,75,5,7,0,76,5,-74, -0,77,5,2,0,78,5,-69,0,-108,5,27,0,-9,5,27,0,80,0,2,0,20,0,2,0,-119,0,7,0,-8,5,9, -0,-7,5,7,0,8,2,7,0,9,2,57,0,1,1,57,0,-6,5,4,0,-5,5,2,0,-89,5,2,0,37,0,-70, -0,-127,5,-51,0,42,0,-75,0,0,0,-75,0,1,0,4,0,75,5,7,0,76,5,-74,0,77,5,2,0,78,5,-69, -0,-108,5,-50,0,-4,5,0,0,-77,5,0,0,-76,5,0,0,-75,5,2,0,18,0,2,0,-66,5,2,0,20,0,2, -0,-73,5,9,0,-7,5,4,0,-3,5,4,0,-2,5,4,0,-1,5,4,0,0,6,23,0,1,6,23,0,2,6,7, -0,3,6,7,0,4,6,7,0,5,6,7,0,-8,5,2,0,-67,5,2,0,-48,0,2,0,102,1,2,0,6,6,2, -0,37,0,2,0,43,0,2,0,7,6,2,0,8,6,9,0,-64,5,9,0,-63,5,9,0,-62,5,9,0,-61,5,9, -0,-60,5,2,0,-59,5,0,0,-58,5,56,0,9,6,-49,0,20,0,0,0,10,6,0,0,11,6,0,0,12,6,0, -0,13,6,0,0,14,6,0,0,15,6,0,0,16,6,0,0,17,6,0,0,18,6,0,0,19,6,0,0,20,6,0, -0,21,6,0,0,22,6,0,0,23,6,0,0,24,6,0,0,25,6,0,0,26,6,0,0,27,6,0,0,68,2,0, -0,28,6,-48,0,54,0,0,0,29,6,0,0,20,6,0,0,21,6,0,0,30,6,0,0,31,6,0,0,32,6,0, -0,33,6,0,0,34,6,0,0,35,6,0,0,36,6,0,0,37,6,0,0,38,6,0,0,39,6,0,0,40,6,0, -0,41,6,0,0,42,6,0,0,43,6,0,0,44,6,0,0,45,6,0,0,46,6,0,0,47,6,0,0,48,6,0, -0,49,6,0,0,50,6,0,0,51,6,0,0,52,6,0,0,53,6,0,0,54,6,0,0,55,6,0,0,56,6,0, -0,57,6,0,0,58,6,0,0,95,0,0,0,59,6,0,0,60,6,0,0,61,6,0,0,62,6,0,0,63,6,0, -0,64,6,0,0,65,6,0,0,66,6,0,0,67,6,0,0,68,6,0,0,69,6,0,0,70,6,0,0,71,6,0, -0,72,6,0,0,73,6,0,0,74,6,0,0,75,6,0,0,76,6,0,0,77,6,0,0,78,6,0,0,79,6,-47, -0,5,0,0,0,80,6,0,0,37,6,0,0,39,6,2,0,20,0,2,0,37,0,-46,0,22,0,-46,0,0,0,-46, -0,1,0,0,0,17,0,-49,0,81,6,-48,0,82,6,-48,0,83,6,-48,0,84,6,-48,0,85,6,-48,0,86,6,-48, -0,87,6,-48,0,88,6,-48,0,89,6,-48,0,90,6,-48,0,91,6,-48,0,92,6,-48,0,93,6,-48,0,94,6,-48, -0,95,6,-48,0,96,6,-47,0,97,6,0,0,98,6,0,0,99,6,-45,0,5,0,4,0,20,0,4,0,37,0,7, -0,52,2,7,0,100,6,7,0,-31,1,-44,0,66,0,4,0,20,0,4,0,101,6,4,0,102,6,0,0,103,6,0, -0,104,6,0,0,105,6,0,0,106,6,0,0,107,6,0,0,108,6,0,0,109,6,0,0,110,6,0,0,111,6,2, -0,112,6,2,0,113,6,4,0,114,6,4,0,115,6,4,0,116,6,4,0,117,6,2,0,118,6,2,0,119,6,2, -0,120,6,2,0,121,6,4,0,122,6,4,0,123,6,2,0,124,6,2,0,125,6,2,0,126,6,2,0,127,6,0, -0,-128,6,12,0,-127,6,2,0,-126,6,2,0,-125,6,2,0,-124,6,2,0,-123,6,2,0,-122,6,2,0,-121,6,2, -0,-120,6,2,0,-119,6,-45,0,-118,6,2,0,-117,6,2,0,-116,6,2,0,-115,6,2,0,-114,6,4,0,-113,6,4, -0,-112,6,4,0,-111,6,4,0,-110,6,2,0,-109,6,2,0,-108,6,2,0,-107,6,2,0,-106,6,2,0,-105,6,2, -0,-104,6,2,0,-103,6,2,0,-102,6,2,0,-101,6,2,0,-100,6,2,0,-99,6,2,0,37,0,0,0,-98,6,0, -0,-97,6,0,0,-96,6,7,0,-95,6,2,0,55,5,2,0,-94,6,54,0,-93,6,-43,0,18,0,27,0,31,0,12, -0,-92,6,12,0,-91,6,12,0,-90,6,-79,0,-89,6,2,0,-105,2,2,0,-88,6,2,0,-104,2,2,0,-87,6,2, -0,-86,6,2,0,-85,6,2,0,-84,6,2,0,-83,6,2,0,-82,6,2,0,37,0,2,0,-81,6,2,0,-80,6,2, -0,-79,6,-42,0,5,0,-42,0,0,0,-42,0,1,0,-42,0,-78,6,13,0,-77,6,4,0,20,0,-41,0,7,0,-41, -0,0,0,-41,0,1,0,-42,0,-76,6,-42,0,-75,6,2,0,123,4,2,0,20,0,4,0,37,0,-40,0,17,0,-40, -0,0,0,-40,0,1,0,0,0,-74,6,0,0,-73,6,0,0,-72,6,2,0,-71,6,2,0,-70,6,2,0,-86,6,2, -0,-85,6,2,0,20,0,2,0,70,3,2,0,-69,6,2,0,-68,6,2,0,-67,6,2,0,-66,6,4,0,-65,6,-40, -0,-64,6,-74,0,30,0,-74,0,0,0,-74,0,1,0,-42,0,-76,6,-42,0,-75,6,-42,0,-63,6,-42,0,-62,6,-43, -0,-61,6,7,0,-60,6,23,0,52,0,23,0,-59,6,23,0,-58,6,2,0,-57,6,2,0,-56,6,2,0,-55,6,0, -0,75,5,0,0,-54,6,2,0,-53,6,2,0,-52,6,0,0,-51,6,0,0,-50,6,0,0,-49,6,0,0,-48,6,2, -0,-47,6,2,0,-46,6,2,0,-45,6,2,0,20,0,39,0,125,0,12,0,-44,6,12,0,-43,6,12,0,-42,6,-39, -0,11,0,0,0,-41,6,2,0,-40,6,2,0,-39,6,2,0,-38,6,2,0,-37,6,2,0,-36,6,2,0,107,4,9, -0,-35,6,9,0,-34,6,4,0,-33,6,4,0,-32,6,-38,0,1,0,0,0,-31,6,-37,0,8,0,56,0,-30,6,56, -0,-29,6,-37,0,-28,6,-37,0,-27,6,-37,0,-26,6,2,0,-123,0,2,0,20,0,4,0,-25,6,-36,0,4,0,4, -0,-35,5,4,0,-24,6,4,0,-31,5,4,0,-23,6,-35,0,2,0,4,0,-22,6,4,0,-21,6,-34,0,9,0,7, -0,-20,6,7,0,-19,6,7,0,-18,6,4,0,20,0,4,0,13,1,7,0,-19,3,7,0,-17,6,4,0,37,0,-33, -0,-16,6,-32,0,6,0,0,0,-15,6,0,0,-75,5,48,0,-116,0,2,0,109,0,2,0,111,4,4,0,37,0,-31, -0,21,0,-31,0,0,0,-31,0,1,0,4,0,57,0,4,0,23,0,4,0,28,0,4,0,-14,6,4,0,-13,6,4, -0,-12,6,-38,0,-11,6,0,0,-15,6,4,0,-10,6,4,0,-9,6,-32,0,-12,2,-36,0,-8,6,-35,0,-7,6,-34, -0,-6,6,-37,0,-5,6,-37,0,-4,6,-37,0,-3,6,56,0,-2,6,56,0,-1,6,-30,0,12,0,0,0,-68,1,9, -0,-62,0,0,0,-61,0,4,0,-58,0,4,0,-50,0,9,0,-57,0,7,0,-55,0,7,0,-54,0,9,0,0,7,9, -0,1,7,9,0,-53,0,9,0,-51,0,-29,0,43,0,-29,0,0,0,-29,0,1,0,9,0,2,7,9,0,26,0,0, -0,27,0,4,0,20,0,4,0,18,0,4,0,23,0,4,0,91,0,4,0,3,7,4,0,4,7,4,0,-13,6,4, -0,-12,6,4,0,5,7,4,0,-39,0,4,0,6,7,4,0,7,7,7,0,8,7,7,0,9,7,4,0,-126,0,4, -0,10,7,-31,0,11,7,36,0,79,0,-79,0,-89,6,48,0,-116,0,7,0,12,7,7,0,13,7,-30,0,2,1,-29, -0,14,7,-29,0,15,7,-29,0,16,7,12,0,17,7,-28,0,18,7,-27,0,19,7,7,0,20,7,7,0,21,7,4, -0,-84,6,7,0,22,7,9,0,23,7,4,0,24,7,4,0,25,7,4,0,26,7,7,0,27,7,-26,0,4,0,-26, -0,0,0,-26,0,1,0,12,0,28,7,-29,0,29,7,-25,0,6,0,12,0,30,7,12,0,17,7,12,0,31,7,2, -0,20,0,2,0,37,0,4,0,57,0,-24,0,4,0,7,0,32,7,7,0,112,0,2,0,33,7,2,0,34,7,-23, -0,6,0,7,0,35,7,7,0,36,7,7,0,37,7,7,0,38,7,4,0,39,7,4,0,40,7,-22,0,12,0,7, -0,41,7,7,0,42,7,7,0,43,7,7,0,44,7,7,0,45,7,7,0,46,7,7,0,47,7,7,0,48,7,7, -0,49,7,7,0,50,7,4,0,-110,2,4,0,51,7,-21,0,2,0,7,0,-55,4,7,0,37,0,-20,0,7,0,7, -0,52,7,7,0,53,7,4,0,93,0,4,0,108,2,4,0,54,7,4,0,55,7,4,0,37,0,-19,0,6,0,-19, -0,0,0,-19,0,1,0,2,0,18,0,2,0,20,0,2,0,56,7,2,0,57,0,-18,0,8,0,-18,0,0,0,-18, -0,1,0,2,0,18,0,2,0,20,0,2,0,56,7,2,0,57,0,7,0,23,0,7,0,-126,0,-17,0,45,0,-17, -0,0,0,-17,0,1,0,2,0,18,0,2,0,20,0,2,0,56,7,2,0,-43,0,2,0,-103,3,2,0,57,7,7, -0,58,7,7,0,92,0,7,0,-97,2,4,0,59,7,4,0,81,0,4,0,110,2,7,0,60,7,7,0,61,7,7, -0,62,7,7,0,63,7,7,0,64,7,7,0,65,7,7,0,-100,2,7,0,-1,0,7,0,66,7,7,0,67,7,7, -0,37,0,7,0,68,7,7,0,69,7,7,0,70,7,2,0,71,7,2,0,72,7,2,0,73,7,2,0,74,7,2, -0,75,7,2,0,76,7,2,0,77,7,2,0,78,7,2,0,123,5,2,0,79,7,2,0,-47,1,2,0,80,7,0, -0,81,7,0,0,82,7,7,0,-45,0,-16,0,83,7,63,0,-95,1,-15,0,16,0,-15,0,0,0,-15,0,1,0,2, -0,18,0,2,0,20,0,2,0,56,7,2,0,-43,0,7,0,-105,2,7,0,-104,2,7,0,-103,2,7,0,-5,1,7, -0,-102,2,7,0,-101,2,7,0,84,7,7,0,-100,2,7,0,-98,2,7,0,-97,2,-59,0,5,0,2,0,18,0,2, -0,-25,6,2,0,20,0,2,0,85,7,27,0,-9,5,-60,0,3,0,4,0,69,0,4,0,86,7,-59,0,2,0,-14, -0,12,0,-14,0,0,0,-14,0,1,0,2,0,18,0,2,0,20,0,2,0,31,3,2,0,-32,1,7,0,5,0,7, -0,6,0,7,0,87,7,7,0,88,7,27,0,-9,5,12,0,89,7,-13,0,11,0,-13,0,0,0,-13,0,1,0,0, -0,17,0,2,0,18,0,2,0,90,7,4,0,22,0,4,0,91,7,2,0,20,0,2,0,37,0,9,0,92,7,9, -0,93,7,-12,0,5,0,0,0,17,0,7,0,20,1,7,0,94,7,4,0,95,7,4,0,37,0,-11,0,4,0,2, -0,18,0,2,0,20,0,2,0,43,0,2,0,70,0,-10,0,4,0,0,0,17,0,62,0,96,7,7,0,20,1,7, -0,37,0,-9,0,6,0,2,0,97,7,2,0,98,7,2,0,18,0,2,0,99,7,0,0,100,7,0,0,101,7,-8, -0,5,0,4,0,18,0,4,0,37,0,0,0,17,0,0,0,102,7,0,0,103,7,-7,0,3,0,4,0,18,0,4, -0,37,0,0,0,17,0,-6,0,4,0,2,0,104,7,2,0,105,7,2,0,20,0,2,0,37,0,-5,0,6,0,0, -0,17,0,0,0,106,7,2,0,107,7,2,0,-100,2,2,0,13,1,2,0,70,0,-4,0,5,0,0,0,17,0,7, -0,112,0,7,0,-17,3,2,0,20,0,2,0,122,2,-3,0,3,0,0,0,17,0,4,0,110,2,4,0,104,7,-2, -0,7,0,0,0,17,0,7,0,-17,3,0,0,108,7,0,0,109,7,2,0,13,1,2,0,43,0,4,0,110,7,-1, -0,3,0,32,0,111,7,0,0,112,7,0,0,113,7,0,1,18,0,0,1,0,0,0,1,1,0,2,0,18,0,2, -0,90,7,2,0,20,0,2,0,114,7,2,0,115,7,2,0,116,7,2,0,43,0,2,0,70,0,0,0,17,0,9, -0,2,0,1,1,117,7,32,0,45,0,2,0,-47,4,2,0,20,7,2,0,118,7,2,0,37,0,2,1,11,0,0, -0,17,0,0,0,18,0,0,0,119,7,2,0,20,0,2,0,122,2,2,0,120,7,4,0,121,7,4,0,122,7,4, -0,123,7,4,0,124,7,4,0,125,7,3,1,1,0,0,0,126,7,4,1,4,0,42,0,-36,5,0,0,127,7,4, -0,13,1,4,0,20,0,1,1,18,0,1,1,0,0,1,1,1,0,1,1,-128,7,2,0,18,0,2,0,20,0,2, -0,-127,7,2,0,116,7,2,0,90,7,2,0,-126,7,2,0,70,0,2,0,12,1,0,0,17,0,9,0,2,0,5, -1,117,7,0,1,-125,7,2,0,15,0,2,0,-124,7,4,0,-123,7,6,1,3,0,4,0,-74,2,4,0,37,0,32, -0,45,0,7,1,12,0,-111,0,-122,7,2,0,18,0,2,0,20,0,4,0,58,7,4,0,92,0,0,0,17,0,0, -0,-121,7,2,0,-120,7,2,0,-119,7,2,0,-118,7,2,0,-117,7,7,0,-116,7,8,1,10,0,2,0,20,0,2, -0,-115,7,4,0,58,7,4,0,92,0,2,0,-114,7,-28,0,18,7,2,0,18,0,2,0,-113,7,2,0,-112,7,2, -0,-111,7,9,1,7,0,2,0,20,0,2,0,-115,7,4,0,58,7,4,0,92,0,2,0,18,0,2,0,-110,7,7, -0,109,3,10,1,11,0,4,0,-74,2,2,0,18,0,2,0,20,0,32,0,45,0,74,0,-109,7,0,0,17,0,7, -0,-108,7,7,0,-107,7,7,0,21,3,2,0,-106,7,2,0,-105,7,11,1,5,0,2,0,18,0,2,0,20,0,4, -0,37,0,-79,0,-89,6,32,0,39,5,12,1,5,0,4,0,20,0,4,0,18,0,0,0,17,0,0,0,102,7,32, -0,45,0,13,1,13,0,2,0,20,0,2,0,18,0,2,0,90,7,2,0,22,3,7,0,-104,7,7,0,-103,7,7, -0,7,1,7,0,8,1,7,0,-3,2,7,0,0,3,7,0,-102,7,7,0,-101,7,32,0,-100,7,14,1,10,0,2, -0,20,0,2,0,18,0,4,0,58,7,4,0,92,0,0,0,17,0,0,0,-121,7,2,0,43,0,2,0,64,0,2, -0,-99,7,2,0,-98,7,15,1,8,0,32,0,45,0,7,0,-103,2,7,0,-97,7,7,0,-96,7,7,0,-108,2,2, -0,20,0,2,0,122,2,7,0,-95,7,16,1,12,0,2,0,18,0,2,0,13,1,2,0,20,0,2,0,-100,2,2, -0,-74,2,2,0,-94,7,4,0,37,0,7,0,-93,7,7,0,-92,7,7,0,-91,7,7,0,-90,7,0,0,-89,7,17, -1,10,0,2,0,20,0,2,0,18,0,4,0,58,7,4,0,92,0,0,0,17,0,2,0,68,2,2,0,64,0,2, -0,-99,7,2,0,-98,7,63,0,-95,1,18,1,7,0,4,0,110,2,4,0,-88,7,4,0,-87,7,4,0,-86,7,7, -0,-85,7,7,0,-84,7,0,0,108,7,19,1,7,0,0,0,-83,7,32,0,-82,7,0,0,112,7,2,0,-81,7,2, -0,43,0,4,0,70,0,0,0,113,7,20,1,6,0,2,0,20,0,2,0,18,0,4,0,58,7,4,0,92,0,0, -0,-80,7,0,0,-79,7,21,1,1,0,4,0,20,0,22,1,6,0,0,0,95,0,2,0,18,0,2,0,20,0,4, -0,-78,7,7,0,-77,7,42,0,-36,5,23,1,4,0,0,0,-74,0,2,0,20,0,4,0,18,0,32,0,45,0,24, -1,2,0,4,0,18,0,4,0,-121,5,5,1,10,0,5,1,0,0,5,1,1,0,5,1,-128,7,2,0,18,0,2, -0,20,0,2,0,90,7,2,0,-76,7,0,0,17,0,9,0,2,0,32,0,45,0,25,1,10,0,7,0,21,3,7, -0,-75,7,7,0,-74,7,7,0,-73,7,7,0,-72,7,4,0,20,0,7,0,-94,7,7,0,-71,7,7,0,-70,7,7, -0,37,0,-28,0,20,0,27,0,31,0,0,0,-63,0,26,1,-69,7,9,0,-68,7,43,0,-104,0,43,0,-67,7,9, -0,-66,7,36,0,79,0,7,0,109,3,7,0,-65,7,7,0,-64,7,7,0,-63,7,7,0,-62,7,7,0,-61,7,7, -0,-60,7,4,0,93,0,4,0,-59,7,0,0,-58,7,0,0,-57,7,0,0,-56,7,27,1,6,0,27,0,31,0,7, -0,-55,7,7,0,-54,7,7,0,-53,7,2,0,-52,7,2,0,-51,7,28,1,14,0,-75,0,0,0,-75,0,1,0,4, -0,75,5,7,0,76,5,-74,0,77,5,-69,0,-108,5,-28,0,18,7,2,0,13,1,2,0,-115,7,2,0,8,2,2, -0,9,2,2,0,20,0,2,0,-98,5,4,0,70,0,29,1,6,0,29,1,0,0,29,1,1,0,32,0,45,0,9, -0,-50,7,4,0,-38,0,4,0,37,0,63,0,4,0,27,0,31,0,12,0,-49,7,4,0,-121,0,7,0,-48,7,30, -1,25,0,30,1,0,0,30,1,1,0,30,1,38,0,12,0,-47,7,0,0,17,0,7,0,-46,7,7,0,-45,7,7, -0,-44,7,7,0,-43,7,4,0,20,0,7,0,-42,7,7,0,-41,7,7,0,-40,7,7,0,20,1,7,0,-39,1,7, -0,-39,7,7,0,108,2,7,0,-38,7,7,0,-37,7,7,0,-36,7,7,0,-35,7,7,0,-34,7,7,0,-81,0,2, -0,-121,0,2,0,-31,4,31,1,19,0,27,0,31,0,12,0,-33,7,12,0,-32,7,4,0,20,0,4,0,30,4,2, -0,-96,2,2,0,-31,7,2,0,-121,0,2,0,-30,7,2,0,-29,7,2,0,-28,7,2,0,-27,7,2,0,-26,7,4, -0,-25,7,4,0,-24,7,4,0,-23,7,4,0,-22,7,4,0,-21,7,4,0,-20,7,32,1,34,0,32,1,0,0,32, -1,1,0,12,0,49,3,0,0,17,0,2,0,20,0,2,0,-19,7,2,0,-18,7,2,0,-17,7,2,0,10,3,2, -0,-16,7,4,0,-7,1,4,0,-23,7,4,0,-22,7,30,1,-15,7,32,1,38,0,32,1,-14,7,12,0,-13,7,9, -0,-12,7,9,0,-11,7,9,0,-10,7,7,0,7,1,7,0,-81,0,7,0,-57,1,7,0,-9,7,7,0,-8,7,7, -0,2,3,7,0,-7,7,7,0,-6,7,7,0,-5,7,7,0,-4,7,7,0,-3,7,7,0,-2,7,7,0,-10,1,32, -0,-1,7,-110,0,9,0,12,0,0,8,2,0,20,0,2,0,1,8,7,0,20,3,7,0,2,8,7,0,3,8,12, -0,4,8,4,0,5,8,4,0,37,0,33,1,7,0,33,1,0,0,33,1,1,0,12,0,-58,7,4,0,20,0,4, -0,6,8,0,0,17,0,-47,0,7,8,34,1,8,0,34,1,0,0,34,1,1,0,33,1,8,8,36,0,79,0,12, -0,-6,2,4,0,20,0,0,0,17,0,4,0,9,8,-111,0,6,0,27,0,31,0,12,0,0,8,12,0,10,8,12, -0,103,0,4,0,11,8,4,0,37,0,35,1,16,0,-75,0,0,0,-75,0,1,0,4,0,75,5,7,0,76,5,-74, -0,77,5,2,0,78,5,-69,0,-108,5,-111,0,-9,2,0,0,13,1,0,0,-37,5,2,0,20,0,2,0,12,8,2, -0,-101,5,2,0,-98,5,2,0,13,8,7,0,14,8,36,1,5,0,36,1,0,0,36,1,1,0,36,0,79,0,2, -0,20,0,0,0,15,8,37,1,12,0,37,1,0,0,37,1,1,0,9,0,2,0,2,0,18,0,2,0,20,0,0, -0,16,8,0,0,17,8,0,0,15,8,7,0,18,8,7,0,19,8,4,0,37,0,36,0,79,0,38,1,9,0,38, -1,0,0,38,1,1,0,32,0,20,8,0,0,21,8,7,0,22,8,2,0,23,8,2,0,20,0,2,0,18,0,2, -0,37,0,39,1,7,0,42,0,-36,5,26,0,24,8,4,0,20,0,4,0,25,8,12,0,26,8,32,0,20,8,0, -0,21,8,40,1,12,0,32,0,20,8,2,0,27,8,2,0,20,0,2,0,28,8,2,0,29,8,0,0,21,8,32, -0,30,8,0,0,31,8,7,0,32,8,7,0,-39,1,7,0,33,8,7,0,34,8,41,1,6,0,32,0,20,8,4, -0,9,8,4,0,35,8,4,0,93,0,4,0,37,0,0,0,21,8,42,1,4,0,32,0,20,8,4,0,20,0,4, -0,9,8,0,0,21,8,43,1,4,0,32,0,20,8,4,0,20,0,4,0,9,8,0,0,21,8,44,1,10,0,32, -0,20,8,4,0,36,8,7,0,-127,0,4,0,20,0,2,0,-42,5,2,0,37,8,2,0,43,0,2,0,70,0,7, -0,38,8,0,0,21,8,45,1,4,0,32,0,20,8,4,0,20,0,4,0,9,8,0,0,21,8,46,1,10,0,32, -0,20,8,2,0,18,0,2,0,-95,3,4,0,91,0,4,0,92,0,7,0,-97,7,7,0,-96,7,4,0,37,0,-111, -0,-122,7,0,0,21,8,47,1,4,0,32,0,20,8,4,0,7,3,4,0,39,8,0,0,21,8,48,1,5,0,32, -0,20,8,7,0,-127,0,4,0,40,8,4,0,7,3,4,0,8,3,49,1,6,0,32,0,20,8,4,0,41,8,4, -0,42,8,7,0,43,8,7,0,44,8,0,0,21,8,50,1,16,0,32,0,20,8,32,0,-14,7,4,0,18,0,7, -0,45,8,7,0,46,8,7,0,47,8,7,0,48,8,7,0,49,8,7,0,50,8,7,0,51,8,7,0,52,8,7, -0,53,8,2,0,20,0,2,0,37,0,2,0,43,0,2,0,70,0,51,1,3,0,32,0,20,8,4,0,20,0,4, -0,123,5,52,1,5,0,32,0,20,8,4,0,20,0,4,0,37,0,7,0,54,8,0,0,21,8,53,1,10,0,32, -0,20,8,0,0,21,8,2,0,55,8,2,0,56,8,0,0,57,8,0,0,58,8,7,0,59,8,7,0,60,8,7, -0,61,8,7,0,62,8,54,1,8,0,7,0,9,0,7,0,10,0,7,0,11,0,7,0,12,0,7,0,63,8,7, -0,64,8,2,0,20,0,2,0,123,5,55,1,8,0,7,0,9,0,7,0,10,0,7,0,11,0,7,0,12,0,7, -0,63,8,7,0,64,8,2,0,20,0,2,0,123,5,56,1,8,0,7,0,9,0,7,0,10,0,7,0,11,0,7, -0,12,0,7,0,63,8,7,0,64,8,2,0,20,0,2,0,123,5,57,1,7,0,32,0,20,8,0,0,21,8,7, -0,20,1,7,0,30,1,2,0,20,0,2,0,13,1,4,0,37,0,58,1,5,0,32,0,-45,2,7,0,20,1,2, -0,-41,2,0,0,-39,2,0,0,65,8,59,1,10,0,59,1,0,0,59,1,1,0,2,0,18,0,2,0,20,0,0, -0,66,8,7,0,-36,0,7,0,-35,0,2,0,-58,7,2,0,67,8,32,0,45,0,60,1,22,0,60,1,0,0,60, -1,1,0,2,0,20,0,2,0,13,1,2,0,68,8,2,0,69,8,36,0,79,0,-111,0,-122,7,32,0,-89,0,7, -0,91,0,7,0,92,0,7,0,70,8,7,0,71,8,7,0,72,8,7,0,73,8,7,0,-107,2,7,0,-67,1,7, -0,-120,7,7,0,74,8,0,0,75,8,0,0,76,8,12,0,-4,2,61,1,8,0,7,0,-31,1,7,0,-97,7,7, -0,-96,7,9,0,2,0,2,0,77,8,2,0,78,8,2,0,79,8,2,0,80,8,62,1,18,0,62,1,0,0,62, -1,1,0,62,1,81,8,0,0,17,0,61,1,82,8,2,0,18,0,2,0,20,0,2,0,83,8,2,0,84,8,2, -0,85,8,2,0,86,8,4,0,43,0,7,0,87,8,7,0,88,8,4,0,89,8,4,0,90,8,62,1,91,8,63, -1,92,8,64,1,32,0,64,1,0,0,64,1,1,0,64,1,93,8,0,0,17,0,0,0,94,8,2,0,18,0,2, -0,20,0,2,0,-14,6,2,0,20,7,2,0,95,8,2,0,-119,0,2,0,84,8,2,0,-25,6,12,0,-127,7,12, -0,96,8,27,0,-9,5,9,0,97,8,7,0,87,8,7,0,88,8,7,0,-5,1,7,0,98,8,2,0,99,8,2, -0,100,8,7,0,101,8,7,0,102,8,2,0,103,8,2,0,104,8,24,0,105,8,24,0,106,8,24,0,107,8,65, -1,-103,0,66,1,108,8,63,1,6,0,63,1,0,0,63,1,1,0,64,1,109,8,64,1,110,8,62,1,111,8,62, -1,91,8,57,0,16,0,27,0,31,0,12,0,112,8,12,0,113,8,61,1,114,8,12,0,115,8,4,0,18,0,4, -0,116,8,4,0,117,8,4,0,118,8,12,0,119,8,66,1,120,8,62,1,121,8,62,1,122,8,9,0,123,8,9, -0,124,8,4,0,125,8,67,1,6,0,4,0,-128,0,4,0,-126,0,4,0,-25,6,0,0,126,8,0,0,127,8,2, -0,37,0,68,1,16,0,2,0,-86,6,2,0,-85,6,2,0,-128,8,2,0,-74,7,2,0,-127,8,2,0,68,0,7, -0,-108,2,7,0,-126,8,7,0,-125,8,2,0,34,1,0,0,-124,8,0,0,42,4,2,0,-123,8,2,0,37,0,4, -0,-122,8,4,0,-121,8,69,1,9,0,7,0,-120,8,7,0,-119,8,7,0,-60,7,7,0,112,0,7,0,-118,8,7, -0,71,5,2,0,-117,8,0,0,-116,8,0,0,37,0,70,1,4,0,7,0,-115,8,7,0,-114,8,2,0,-117,8,2, -0,37,0,71,1,3,0,7,0,-113,8,7,0,-112,8,7,0,15,0,72,1,7,0,0,0,-68,1,2,0,109,4,2, -0,110,4,2,0,111,4,2,0,62,4,4,0,-126,0,4,0,-97,3,73,1,7,0,7,0,-111,8,7,0,-110,8,7, -0,-109,8,7,0,4,2,7,0,-108,8,7,0,-107,8,7,0,-106,8,74,1,4,0,2,0,-105,8,2,0,-104,8,2, -0,-103,8,2,0,-102,8,75,1,2,0,7,0,5,0,7,0,6,0,76,1,2,0,0,0,-87,0,0,0,-101,8,77, -1,1,0,0,0,17,0,78,1,10,0,0,0,-100,8,0,0,-99,8,0,0,-98,8,0,0,-97,8,2,0,-128,8,2, -0,-96,8,7,0,-95,8,7,0,-94,8,7,0,-93,8,7,0,-67,1,79,1,2,0,9,0,-92,8,9,0,-91,8,80, -1,11,0,0,0,111,4,0,0,18,0,0,0,-117,8,0,0,112,0,0,0,-90,8,0,0,109,0,0,0,-74,0,7, -0,-89,8,7,0,-88,8,7,0,-87,8,7,0,-86,8,81,1,8,0,7,0,97,7,7,0,-127,0,7,0,42,4,7, -0,72,2,7,0,-85,8,7,0,-49,0,7,0,-84,8,4,0,18,0,82,1,4,0,2,0,-83,8,2,0,-82,8,2, -0,-81,8,2,0,37,0,83,1,1,0,0,0,17,0,84,1,4,0,7,0,5,0,7,0,6,0,2,0,20,0,2, -0,-80,8,85,1,10,0,2,0,-120,3,2,0,20,0,7,0,-17,3,7,0,-79,8,7,0,-78,8,7,0,-77,8,7, -0,-76,8,84,1,-75,8,84,1,-74,8,84,1,-73,8,60,0,9,0,4,0,20,0,4,0,64,0,24,0,-72,8,24, -0,-71,8,85,1,-70,8,7,0,-69,8,7,0,-68,8,7,0,-67,8,7,0,-66,8,86,1,4,0,46,0,-114,2,7, -0,-65,8,7,0,92,1,7,0,37,0,-87,0,13,0,27,0,31,0,2,0,20,0,2,0,72,5,4,0,109,0,7, -0,-64,8,7,0,1,2,7,0,-63,8,7,0,-62,8,7,0,92,1,2,0,47,1,2,0,37,0,50,0,77,1,86, -1,-61,8,87,1,10,0,4,0,18,0,4,0,-127,0,4,0,20,0,4,0,70,3,4,0,-60,8,4,0,-59,8,4, -0,-58,8,0,0,95,0,0,0,17,0,9,0,2,0,84,0,6,0,87,1,-57,8,4,0,-56,8,4,0,-55,8,4, -0,-54,8,4,0,37,0,9,0,-53,8,88,1,5,0,7,0,66,2,7,0,-74,2,7,0,-39,1,2,0,-52,8,2, -0,37,0,89,1,5,0,7,0,66,2,7,0,-51,8,7,0,-50,8,7,0,-49,8,7,0,-74,2,90,1,7,0,4, -0,-48,8,4,0,-47,8,4,0,-46,8,7,0,-45,8,7,0,-44,8,7,0,-43,8,7,0,-42,8,91,1,26,0,32, -0,-41,8,89,1,66,3,89,1,-40,8,88,1,-39,8,89,1,83,7,7,0,-38,8,7,0,-37,8,7,0,-36,8,7, -0,-35,8,7,0,-44,8,7,0,-43,8,7,0,-74,2,7,0,-97,2,7,0,-34,8,7,0,-33,8,7,0,109,0,7, -0,-32,8,4,0,-48,8,4,0,-31,8,4,0,37,0,4,0,81,0,4,0,-30,8,2,0,20,0,2,0,-29,8,2, -0,-28,8,2,0,100,3,92,1,112,0,27,0,31,0,4,0,20,0,2,0,18,0,2,0,55,8,2,0,-27,8,2, -0,-26,8,2,0,-25,8,2,0,-24,8,2,0,-23,8,2,0,-22,8,2,0,-21,8,2,0,-20,8,2,0,-19,8,2, -0,-18,8,2,0,-17,8,2,0,-16,8,2,0,-15,8,2,0,-14,8,2,0,-13,8,2,0,-47,1,2,0,76,7,2, -0,51,7,2,0,-12,8,2,0,-11,8,2,0,98,3,2,0,99,3,2,0,-10,8,2,0,-9,8,2,0,-8,8,2, -0,-7,8,2,0,-6,8,2,0,-5,8,7,0,-4,8,7,0,-3,8,7,0,-2,8,2,0,-1,8,2,0,0,9,7, -0,1,9,7,0,2,9,7,0,3,9,7,0,58,7,7,0,92,0,7,0,-97,2,7,0,64,7,7,0,4,9,7, -0,5,9,7,0,6,9,7,0,7,9,7,0,57,0,4,0,59,7,4,0,57,7,4,0,8,9,7,0,60,7,7, -0,61,7,7,0,62,7,7,0,9,9,7,0,10,9,7,0,11,9,7,0,12,9,7,0,13,9,7,0,14,9,7, -0,15,9,7,0,16,9,7,0,21,3,7,0,109,0,7,0,17,9,7,0,18,9,7,0,19,9,7,0,20,9,7, -0,21,9,7,0,22,9,7,0,108,2,7,0,23,9,7,0,24,9,4,0,25,9,4,0,26,9,7,0,27,9,7, -0,28,9,7,0,29,9,7,0,30,9,7,0,31,9,7,0,32,9,7,0,33,9,7,0,34,9,7,0,94,3,7, -0,92,3,7,0,93,3,7,0,35,9,7,0,36,9,7,0,37,9,7,0,38,9,7,0,39,9,7,0,40,9,7, -0,41,9,7,0,42,9,7,0,43,9,7,0,28,3,7,0,44,9,7,0,45,9,7,0,46,9,7,0,47,9,7, -0,48,9,7,0,49,9,7,0,50,9,0,0,51,9,63,0,55,3,63,0,52,9,32,0,53,9,32,0,54,9,36, -0,79,0,-108,0,53,3,-108,0,55,9,-120,0,37,0,-120,0,0,0,-120,0,1,0,92,1,56,9,91,1,-121,3,90, -1,-14,7,93,1,57,9,94,1,58,9,94,1,59,9,12,0,60,9,12,0,61,9,-107,0,54,3,32,0,62,9,32, -0,63,9,32,0,64,9,12,0,65,9,12,0,66,9,7,0,-45,0,7,0,83,4,4,0,110,2,4,0,20,0,4, -0,59,7,4,0,67,9,4,0,68,9,4,0,69,9,4,0,57,0,2,0,-38,0,2,0,70,9,2,0,71,9,2, -0,72,9,2,0,47,3,2,0,73,9,0,0,74,9,2,0,75,9,2,0,76,9,2,0,77,9,9,0,78,9,125, -0,-76,3,123,0,34,0,95,1,79,9,7,0,-106,3,7,0,80,9,7,0,81,9,7,0,-14,3,7,0,82,9,7, -0,31,3,7,0,21,3,7,0,83,9,7,0,3,2,7,0,84,9,7,0,85,9,7,0,86,9,7,0,87,9,7, -0,88,9,7,0,89,9,7,0,-105,3,7,0,90,9,7,0,91,9,7,0,92,9,7,0,-104,3,7,0,-108,3,7, -0,-107,3,4,0,93,9,4,0,93,0,4,0,94,9,4,0,95,9,2,0,96,9,2,0,97,9,2,0,98,9,2, -0,99,9,2,0,100,9,2,0,37,0,4,0,70,0,124,0,8,0,95,1,101,9,7,0,102,9,7,0,103,9,7, -0,-94,1,7,0,104,9,4,0,93,0,2,0,105,9,2,0,106,9,96,1,4,0,7,0,5,0,7,0,6,0,7, -0,7,0,7,0,107,9,97,1,6,0,97,1,0,0,97,1,1,0,96,1,108,9,4,0,109,9,2,0,110,9,2, -0,20,0,98,1,5,0,98,1,0,0,98,1,1,0,12,0,111,9,4,0,112,9,4,0,20,0,99,1,9,0,99, -1,0,0,99,1,1,0,12,0,-128,0,98,1,113,9,4,0,20,0,2,0,110,9,2,0,114,9,7,0,94,0,0, -0,115,9,-70,0,5,0,12,0,125,4,4,0,20,0,2,0,116,9,2,0,117,9,9,0,118,9,69,78,68,66,0, -0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 -}; -int DNAlen= sizeof(DNAstr); diff --git a/extern/bullet/src/Extras/Serialize/BulletFileLoader/CMakeLists.txt b/extern/bullet/src/Extras/Serialize/BulletFileLoader/CMakeLists.txt deleted file mode 100644 index 9b5dce7eabd6..000000000000 --- a/extern/bullet/src/Extras/Serialize/BulletFileLoader/CMakeLists.txt +++ /dev/null @@ -1,53 +0,0 @@ -INCLUDE_DIRECTORIES( - ${BULLET_PHYSICS_SOURCE_DIR}/src -) - -SET(BulletFileLoader_SRCS -bChunk.cpp -bDNA.cpp -bFile.cpp -btBulletFile.cpp -) - -SET(BulletFileLoader_HDRS -bChunk.h -bCommon.h -bDefines.h -bDNA.h -bFile.h -btBulletFile.h -) - -ADD_LIBRARY(BulletFileLoader ${BulletFileLoader_SRCS} ${BulletFileLoader_HDRS}) - -IF (BUILD_SHARED_LIBS) - TARGET_LINK_LIBRARIES(BulletFileLoader LinearMath) -ENDIF (BUILD_SHARED_LIBS) - -SET_TARGET_PROPERTIES(BulletFileLoader PROPERTIES VERSION ${BULLET_VERSION}) -SET_TARGET_PROPERTIES(BulletFileLoader PROPERTIES SOVERSION ${BULLET_VERSION}) - -IF (INSTALL_EXTRA_LIBS) - IF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES) - #FILES_MATCHING requires CMake 2.6 - IF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5) - IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - INSTALL(TARGETS BulletFileLoader DESTINATION .) - ELSE (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - INSTALL(TARGETS BulletFileLoader - RUNTIME DESTINATION bin - LIBRARY DESTINATION lib${LIB_SUFFIX} - ARCHIVE DESTINATION lib${LIB_SUFFIX}) - INSTALL( - DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} - DESTINATION ${INCLUDE_INSTALL_DIR} FILES_MATCHING PATTERN "*.h" PATTERN - ".svn" EXCLUDE PATTERN "CMakeFiles" EXCLUDE) - ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - ENDIF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5) - - IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - SET_TARGET_PROPERTIES(BulletFileLoader PROPERTIES FRAMEWORK true) - SET_TARGET_PROPERTIES(BulletFileLoader PROPERTIES PUBLIC_HEADER "${BulletFileLoader_HDRS}") - ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - ENDIF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES) -ENDIF (INSTALL_EXTRA_LIBS) diff --git a/extern/bullet/src/Extras/Serialize/BulletFileLoader/autogenerated/bullet.h b/extern/bullet/src/Extras/Serialize/BulletFileLoader/autogenerated/bullet.h deleted file mode 100644 index bebd92ef2900..000000000000 --- a/extern/bullet/src/Extras/Serialize/BulletFileLoader/autogenerated/bullet.h +++ /dev/null @@ -1,1577 +0,0 @@ -/* Copyright (C) 2011 Erwin Coumans & Charlie C -* -* This software is provided 'as-is', without any express or implied -* warranty. In no event will the authors be held liable for any damages -* arising from the use of this software. -* -* Permission is granted to anyone to use this software for any purpose, -* including commercial applications, and to alter it and redistribute it -* freely, subject to the following restrictions: -* -* 1. The origin of this software must not be misrepresented; you must not -* claim that you wrote the original software. If you use this software -* in a product, an acknowledgment in the product documentation would be -* appreciated but is not required. -* 2. Altered source versions must be plainly marked as such, and must not be -* misrepresented as being the original software. -* 3. This notice may not be removed or altered from any source distribution. -*/ -// Auto generated from Bullet/Extras/HeaderGenerator/bulletGenerate.py -#ifndef __BULLET_H__ -#define __BULLET_H__ -namespace Bullet { - -// put an empty struct in the case -typedef struct bInvalidHandle { - int unused; -}bInvalidHandle; - - class PointerArray; - class btPhysicsSystem; - class ListBase; - class btVector3FloatData; - class btVector3DoubleData; - class btQuaternionFloatData; - class btQuaternionDoubleData; - class btMatrix3x3FloatData; - class btMatrix3x3DoubleData; - class btTransformFloatData; - class btTransformDoubleData; - class btBvhSubtreeInfoData; - class btOptimizedBvhNodeFloatData; - class btOptimizedBvhNodeDoubleData; - class btQuantizedBvhNodeData; - class btQuantizedBvhFloatData; - class btQuantizedBvhDoubleData; - class btCollisionShapeData; - class btStaticPlaneShapeData; - class btConvexInternalShapeData; - class btPositionAndRadius; - class btMultiSphereShapeData; - class btIntIndexData; - class btShortIntIndexData; - class btShortIntIndexTripletData; - class btCharIndexTripletData; - class btMeshPartData; - class btStridingMeshInterfaceData; - class btTriangleMeshShapeData; - class btScaledTriangleMeshShapeData; - class btCompoundShapeChildData; - class btCompoundShapeData; - class btCylinderShapeData; - class btConeShapeData; - class btCapsuleShapeData; - class btTriangleInfoData; - class btTriangleInfoMapData; - class btPersistentManifoldDoubleData; - class btPersistentManifoldFloatData; - class btGImpactMeshShapeData; - class btConvexHullShapeData; - class btCollisionObjectDoubleData; - class btCollisionObjectFloatData; - class btContactSolverInfoDoubleData; - class btContactSolverInfoFloatData; - class btDynamicsWorldDoubleData; - class btDynamicsWorldFloatData; - class btRigidBodyFloatData; - class btRigidBodyDoubleData; - class btConstraintInfo1; - class btTypedConstraintFloatData; - class btTypedConstraintData; - class btTypedConstraintDoubleData; - class btPoint2PointConstraintFloatData; - class btPoint2PointConstraintDoubleData2; - class btPoint2PointConstraintDoubleData; - class btHingeConstraintDoubleData; - class btHingeConstraintFloatData; - class btHingeConstraintDoubleData2; - class btConeTwistConstraintDoubleData; - class btConeTwistConstraintData; - class btGeneric6DofConstraintData; - class btGeneric6DofConstraintDoubleData2; - class btGeneric6DofSpringConstraintData; - class btGeneric6DofSpringConstraintDoubleData2; - class btGeneric6DofSpring2ConstraintData; - class btGeneric6DofSpring2ConstraintDoubleData2; - class btSliderConstraintData; - class btSliderConstraintDoubleData; - class btGearConstraintFloatData; - class btGearConstraintDoubleData; - class SoftBodyMaterialData; - class SoftBodyNodeData; - class SoftBodyLinkData; - class SoftBodyFaceData; - class SoftBodyTetraData; - class SoftRigidAnchorData; - class SoftBodyConfigData; - class SoftBodyPoseData; - class SoftBodyClusterData; - class btSoftBodyJointData; - class btSoftBodyFloatData; - class btMultiBodyLinkDoubleData; - class btMultiBodyLinkFloatData; - class btMultiBodyDoubleData; - class btMultiBodyFloatData; - class btMultiBodyLinkColliderFloatData; - class btMultiBodyLinkColliderDoubleData; -// -------------------------------------------------- // - class PointerArray - { - public: - int m_size; - int m_capacity; - void *m_data; - }; - - -// -------------------------------------------------- // - class btPhysicsSystem - { - public: - PointerArray m_collisionShapes; - PointerArray m_collisionObjects; - PointerArray m_constraints; - }; - - -// -------------------------------------------------- // - class ListBase - { - public: - void *first; - void *last; - }; - - -// -------------------------------------------------- // - class btVector3FloatData - { - public: - float m_floats[4]; - }; - - -// -------------------------------------------------- // - class btVector3DoubleData - { - public: - double m_floats[4]; - }; - - -// -------------------------------------------------- // - class btQuaternionFloatData - { - public: - float m_floats[4]; - }; - - -// -------------------------------------------------- // - class btQuaternionDoubleData - { - public: - double m_floats[4]; - }; - - -// -------------------------------------------------- // - class btMatrix3x3FloatData - { - public: - btVector3FloatData m_el[3]; - }; - - -// -------------------------------------------------- // - class btMatrix3x3DoubleData - { - public: - btVector3DoubleData m_el[3]; - }; - - -// -------------------------------------------------- // - class btTransformFloatData - { - public: - btMatrix3x3FloatData m_basis; - btVector3FloatData m_origin; - }; - - -// -------------------------------------------------- // - class btTransformDoubleData - { - public: - btMatrix3x3DoubleData m_basis; - btVector3DoubleData m_origin; - }; - - -// -------------------------------------------------- // - class btBvhSubtreeInfoData - { - public: - int m_rootNodeIndex; - int m_subtreeSize; - short m_quantizedAabbMin[3]; - short m_quantizedAabbMax[3]; - }; - - -// -------------------------------------------------- // - class btOptimizedBvhNodeFloatData - { - public: - btVector3FloatData m_aabbMinOrg; - btVector3FloatData m_aabbMaxOrg; - int m_escapeIndex; - int m_subPart; - int m_triangleIndex; - char m_pad[4]; - }; - - -// -------------------------------------------------- // - class btOptimizedBvhNodeDoubleData - { - public: - btVector3DoubleData m_aabbMinOrg; - btVector3DoubleData m_aabbMaxOrg; - int m_escapeIndex; - int m_subPart; - int m_triangleIndex; - char m_pad[4]; - }; - - -// -------------------------------------------------- // - class btQuantizedBvhNodeData - { - public: - short m_quantizedAabbMin[3]; - short m_quantizedAabbMax[3]; - int m_escapeIndexOrTriangleIndex; - }; - - -// -------------------------------------------------- // - class btQuantizedBvhFloatData - { - public: - btVector3FloatData m_bvhAabbMin; - btVector3FloatData m_bvhAabbMax; - btVector3FloatData m_bvhQuantization; - int m_curNodeIndex; - int m_useQuantization; - int m_numContiguousLeafNodes; - int m_numQuantizedContiguousNodes; - btOptimizedBvhNodeFloatData *m_contiguousNodesPtr; - btQuantizedBvhNodeData *m_quantizedContiguousNodesPtr; - btBvhSubtreeInfoData *m_subTreeInfoPtr; - int m_traversalMode; - int m_numSubtreeHeaders; - }; - - -// -------------------------------------------------- // - class btQuantizedBvhDoubleData - { - public: - btVector3DoubleData m_bvhAabbMin; - btVector3DoubleData m_bvhAabbMax; - btVector3DoubleData m_bvhQuantization; - int m_curNodeIndex; - int m_useQuantization; - int m_numContiguousLeafNodes; - int m_numQuantizedContiguousNodes; - btOptimizedBvhNodeDoubleData *m_contiguousNodesPtr; - btQuantizedBvhNodeData *m_quantizedContiguousNodesPtr; - int m_traversalMode; - int m_numSubtreeHeaders; - btBvhSubtreeInfoData *m_subTreeInfoPtr; - }; - - -// -------------------------------------------------- // - class btCollisionShapeData - { - public: - char *m_name; - int m_shapeType; - char m_padding[4]; - }; - - -// -------------------------------------------------- // - class btStaticPlaneShapeData - { - public: - btCollisionShapeData m_collisionShapeData; - btVector3FloatData m_localScaling; - btVector3FloatData m_planeNormal; - float m_planeConstant; - char m_pad[4]; - }; - - -// -------------------------------------------------- // - class btConvexInternalShapeData - { - public: - btCollisionShapeData m_collisionShapeData; - btVector3FloatData m_localScaling; - btVector3FloatData m_implicitShapeDimensions; - float m_collisionMargin; - int m_padding; - }; - - -// -------------------------------------------------- // - class btPositionAndRadius - { - public: - btVector3FloatData m_pos; - float m_radius; - }; - - -// -------------------------------------------------- // - class btMultiSphereShapeData - { - public: - btConvexInternalShapeData m_convexInternalShapeData; - btPositionAndRadius *m_localPositionArrayPtr; - int m_localPositionArraySize; - char m_padding[4]; - }; - - -// -------------------------------------------------- // - class btIntIndexData - { - public: - int m_value; - }; - - -// -------------------------------------------------- // - class btShortIntIndexData - { - public: - short m_value; - char m_pad[2]; - }; - - -// -------------------------------------------------- // - class btShortIntIndexTripletData - { - public: - short m_values[3]; - char m_pad[2]; - }; - - -// -------------------------------------------------- // - class btCharIndexTripletData - { - public: - char m_values[3]; - char m_pad; - }; - - -// -------------------------------------------------- // - class btMeshPartData - { - public: - btVector3FloatData *m_vertices3f; - btVector3DoubleData *m_vertices3d; - btIntIndexData *m_indices32; - btShortIntIndexTripletData *m_3indices16; - btCharIndexTripletData *m_3indices8; - btShortIntIndexData *m_indices16; - int m_numTriangles; - int m_numVertices; - }; - - -// -------------------------------------------------- // - class btStridingMeshInterfaceData - { - public: - btMeshPartData *m_meshPartsPtr; - btVector3FloatData m_scaling; - int m_numMeshParts; - char m_padding[4]; - }; - - -// -------------------------------------------------- // - class btTriangleMeshShapeData - { - public: - btCollisionShapeData m_collisionShapeData; - btStridingMeshInterfaceData m_meshInterface; - btQuantizedBvhFloatData *m_quantizedFloatBvh; - btQuantizedBvhDoubleData *m_quantizedDoubleBvh; - btTriangleInfoMapData *m_triangleInfoMap; - float m_collisionMargin; - char m_pad3[4]; - }; - - -// -------------------------------------------------- // - class btScaledTriangleMeshShapeData - { - public: - btTriangleMeshShapeData m_trimeshShapeData; - btVector3FloatData m_localScaling; - }; - - -// -------------------------------------------------- // - class btCompoundShapeChildData - { - public: - btTransformFloatData m_transform; - btCollisionShapeData *m_childShape; - int m_childShapeType; - float m_childMargin; - }; - - -// -------------------------------------------------- // - class btCompoundShapeData - { - public: - btCollisionShapeData m_collisionShapeData; - btCompoundShapeChildData *m_childShapePtr; - int m_numChildShapes; - float m_collisionMargin; - }; - - -// -------------------------------------------------- // - class btCylinderShapeData - { - public: - btConvexInternalShapeData m_convexInternalShapeData; - int m_upAxis; - char m_padding[4]; - }; - - -// -------------------------------------------------- // - class btConeShapeData - { - public: - btConvexInternalShapeData m_convexInternalShapeData; - int m_upIndex; - char m_padding[4]; - }; - - -// -------------------------------------------------- // - class btCapsuleShapeData - { - public: - btConvexInternalShapeData m_convexInternalShapeData; - int m_upAxis; - char m_padding[4]; - }; - - -// -------------------------------------------------- // - class btTriangleInfoData - { - public: - int m_flags; - float m_edgeV0V1Angle; - float m_edgeV1V2Angle; - float m_edgeV2V0Angle; - }; - - -// -------------------------------------------------- // - class btTriangleInfoMapData - { - public: - int *m_hashTablePtr; - int *m_nextPtr; - btTriangleInfoData *m_valueArrayPtr; - int *m_keyArrayPtr; - float m_convexEpsilon; - float m_planarEpsilon; - float m_equalVertexThreshold; - float m_edgeDistanceThreshold; - float m_zeroAreaThreshold; - int m_nextSize; - int m_hashTableSize; - int m_numValues; - int m_numKeys; - char m_padding[4]; - }; - - -// -------------------------------------------------- // - class btPersistentManifoldDoubleData - { - public: - btVector3DoubleData m_pointCacheLocalPointA[4]; - btVector3DoubleData m_pointCacheLocalPointB[4]; - btVector3DoubleData m_pointCachePositionWorldOnA[4]; - btVector3DoubleData m_pointCachePositionWorldOnB[4]; - btVector3DoubleData m_pointCacheNormalWorldOnB[4]; - btVector3DoubleData m_pointCacheLateralFrictionDir1[4]; - btVector3DoubleData m_pointCacheLateralFrictionDir2[4]; - double m_pointCacheDistance[4]; - double m_pointCacheAppliedImpulse[4]; - double m_pointCacheCombinedFriction[4]; - double m_pointCacheCombinedRollingFriction[4]; - double m_pointCacheCombinedSpinningFriction[4]; - double m_pointCacheCombinedRestitution[4]; - int m_pointCachePartId0[4]; - int m_pointCachePartId1[4]; - int m_pointCacheIndex0[4]; - int m_pointCacheIndex1[4]; - int m_pointCacheContactPointFlags[4]; - double m_pointCacheAppliedImpulseLateral1[4]; - double m_pointCacheAppliedImpulseLateral2[4]; - double m_pointCacheContactMotion1[4]; - double m_pointCacheContactMotion2[4]; - double m_pointCacheContactCFM[4]; - double m_pointCacheCombinedContactStiffness1[4]; - double m_pointCacheContactERP[4]; - double m_pointCacheCombinedContactDamping1[4]; - double m_pointCacheFrictionCFM[4]; - int m_pointCacheLifeTime[4]; - int m_numCachedPoints; - int m_companionIdA; - int m_companionIdB; - int m_index1a; - int m_objectType; - double m_contactBreakingThreshold; - double m_contactProcessingThreshold; - int m_padding; - btCollisionObjectDoubleData *m_body0; - btCollisionObjectDoubleData *m_body1; - }; - - -// -------------------------------------------------- // - class btPersistentManifoldFloatData - { - public: - btVector3FloatData m_pointCacheLocalPointA[4]; - btVector3FloatData m_pointCacheLocalPointB[4]; - btVector3FloatData m_pointCachePositionWorldOnA[4]; - btVector3FloatData m_pointCachePositionWorldOnB[4]; - btVector3FloatData m_pointCacheNormalWorldOnB[4]; - btVector3FloatData m_pointCacheLateralFrictionDir1[4]; - btVector3FloatData m_pointCacheLateralFrictionDir2[4]; - float m_pointCacheDistance[4]; - float m_pointCacheAppliedImpulse[4]; - float m_pointCacheCombinedFriction[4]; - float m_pointCacheCombinedRollingFriction[4]; - float m_pointCacheCombinedSpinningFriction[4]; - float m_pointCacheCombinedRestitution[4]; - int m_pointCachePartId0[4]; - int m_pointCachePartId1[4]; - int m_pointCacheIndex0[4]; - int m_pointCacheIndex1[4]; - int m_pointCacheContactPointFlags[4]; - float m_pointCacheAppliedImpulseLateral1[4]; - float m_pointCacheAppliedImpulseLateral2[4]; - float m_pointCacheContactMotion1[4]; - float m_pointCacheContactMotion2[4]; - float m_pointCacheContactCFM[4]; - float m_pointCacheCombinedContactStiffness1[4]; - float m_pointCacheContactERP[4]; - float m_pointCacheCombinedContactDamping1[4]; - float m_pointCacheFrictionCFM[4]; - int m_pointCacheLifeTime[4]; - int m_numCachedPoints; - int m_companionIdA; - int m_companionIdB; - int m_index1a; - int m_objectType; - float m_contactBreakingThreshold; - float m_contactProcessingThreshold; - int m_padding; - btCollisionObjectFloatData *m_body0; - btCollisionObjectFloatData *m_body1; - }; - - -// -------------------------------------------------- // - class btGImpactMeshShapeData - { - public: - btCollisionShapeData m_collisionShapeData; - btStridingMeshInterfaceData m_meshInterface; - btVector3FloatData m_localScaling; - float m_collisionMargin; - int m_gimpactSubType; - }; - - -// -------------------------------------------------- // - class btConvexHullShapeData - { - public: - btConvexInternalShapeData m_convexInternalShapeData; - btVector3FloatData *m_unscaledPointsFloatPtr; - btVector3DoubleData *m_unscaledPointsDoublePtr; - int m_numUnscaledPoints; - char m_padding3[4]; - }; - - -// -------------------------------------------------- // - class btCollisionObjectDoubleData - { - public: - void *m_broadphaseHandle; - void *m_collisionShape; - btCollisionShapeData *m_rootCollisionShape; - char *m_name; - btTransformDoubleData m_worldTransform; - btTransformDoubleData m_interpolationWorldTransform; - btVector3DoubleData m_interpolationLinearVelocity; - btVector3DoubleData m_interpolationAngularVelocity; - btVector3DoubleData m_anisotropicFriction; - double m_contactProcessingThreshold; - double m_deactivationTime; - double m_friction; - double m_rollingFriction; - double m_contactDamping; - double m_contactStiffness; - double m_restitution; - double m_hitFraction; - double m_ccdSweptSphereRadius; - double m_ccdMotionThreshold; - int m_hasAnisotropicFriction; - int m_collisionFlags; - int m_islandTag1; - int m_companionId; - int m_activationState1; - int m_internalType; - int m_checkCollideWith; - int m_collisionFilterGroup; - int m_collisionFilterMask; - int m_uniqueId; - }; - - -// -------------------------------------------------- // - class btCollisionObjectFloatData - { - public: - void *m_broadphaseHandle; - void *m_collisionShape; - btCollisionShapeData *m_rootCollisionShape; - char *m_name; - btTransformFloatData m_worldTransform; - btTransformFloatData m_interpolationWorldTransform; - btVector3FloatData m_interpolationLinearVelocity; - btVector3FloatData m_interpolationAngularVelocity; - btVector3FloatData m_anisotropicFriction; - float m_contactProcessingThreshold; - float m_deactivationTime; - float m_friction; - float m_rollingFriction; - float m_contactDamping; - float m_contactStiffness; - float m_restitution; - float m_hitFraction; - float m_ccdSweptSphereRadius; - float m_ccdMotionThreshold; - int m_hasAnisotropicFriction; - int m_collisionFlags; - int m_islandTag1; - int m_companionId; - int m_activationState1; - int m_internalType; - int m_checkCollideWith; - int m_collisionFilterGroup; - int m_collisionFilterMask; - int m_uniqueId; - }; - - -// -------------------------------------------------- // - class btContactSolverInfoDoubleData - { - public: - double m_tau; - double m_damping; - double m_friction; - double m_timeStep; - double m_restitution; - double m_maxErrorReduction; - double m_sor; - double m_erp; - double m_erp2; - double m_globalCfm; - double m_splitImpulsePenetrationThreshold; - double m_splitImpulseTurnErp; - double m_linearSlop; - double m_warmstartingFactor; - double m_maxGyroscopicForce; - double m_singleAxisRollingFrictionThreshold; - int m_numIterations; - int m_solverMode; - int m_restingContactRestitutionThreshold; - int m_minimumSolverBatchSize; - int m_splitImpulse; - char m_padding[4]; - }; - - -// -------------------------------------------------- // - class btContactSolverInfoFloatData - { - public: - float m_tau; - float m_damping; - float m_friction; - float m_timeStep; - float m_restitution; - float m_maxErrorReduction; - float m_sor; - float m_erp; - float m_erp2; - float m_globalCfm; - float m_splitImpulsePenetrationThreshold; - float m_splitImpulseTurnErp; - float m_linearSlop; - float m_warmstartingFactor; - float m_maxGyroscopicForce; - float m_singleAxisRollingFrictionThreshold; - int m_numIterations; - int m_solverMode; - int m_restingContactRestitutionThreshold; - int m_minimumSolverBatchSize; - int m_splitImpulse; - char m_padding[4]; - }; - - -// -------------------------------------------------- // - class btDynamicsWorldDoubleData - { - public: - btContactSolverInfoDoubleData m_solverInfo; - btVector3DoubleData m_gravity; - }; - - -// -------------------------------------------------- // - class btDynamicsWorldFloatData - { - public: - btContactSolverInfoFloatData m_solverInfo; - btVector3FloatData m_gravity; - }; - - -// -------------------------------------------------- // - class btRigidBodyFloatData - { - public: - btCollisionObjectFloatData m_collisionObjectData; - btMatrix3x3FloatData m_invInertiaTensorWorld; - btVector3FloatData m_linearVelocity; - btVector3FloatData m_angularVelocity; - btVector3FloatData m_angularFactor; - btVector3FloatData m_linearFactor; - btVector3FloatData m_gravity; - btVector3FloatData m_gravity_acceleration; - btVector3FloatData m_invInertiaLocal; - btVector3FloatData m_totalForce; - btVector3FloatData m_totalTorque; - float m_inverseMass; - float m_linearDamping; - float m_angularDamping; - float m_additionalDampingFactor; - float m_additionalLinearDampingThresholdSqr; - float m_additionalAngularDampingThresholdSqr; - float m_additionalAngularDampingFactor; - float m_linearSleepingThreshold; - float m_angularSleepingThreshold; - int m_additionalDamping; - }; - - -// -------------------------------------------------- // - class btRigidBodyDoubleData - { - public: - btCollisionObjectDoubleData m_collisionObjectData; - btMatrix3x3DoubleData m_invInertiaTensorWorld; - btVector3DoubleData m_linearVelocity; - btVector3DoubleData m_angularVelocity; - btVector3DoubleData m_angularFactor; - btVector3DoubleData m_linearFactor; - btVector3DoubleData m_gravity; - btVector3DoubleData m_gravity_acceleration; - btVector3DoubleData m_invInertiaLocal; - btVector3DoubleData m_totalForce; - btVector3DoubleData m_totalTorque; - double m_inverseMass; - double m_linearDamping; - double m_angularDamping; - double m_additionalDampingFactor; - double m_additionalLinearDampingThresholdSqr; - double m_additionalAngularDampingThresholdSqr; - double m_additionalAngularDampingFactor; - double m_linearSleepingThreshold; - double m_angularSleepingThreshold; - int m_additionalDamping; - char m_padding[4]; - }; - - -// -------------------------------------------------- // - class btConstraintInfo1 - { - public: - int m_numConstraintRows; - int nub; - }; - - -// -------------------------------------------------- // - class btTypedConstraintFloatData - { - public: - btRigidBodyFloatData *m_rbA; - btRigidBodyFloatData *m_rbB; - char *m_name; - int m_objectType; - int m_userConstraintType; - int m_userConstraintId; - int m_needsFeedback; - float m_appliedImpulse; - float m_dbgDrawSize; - int m_disableCollisionsBetweenLinkedBodies; - int m_overrideNumSolverIterations; - float m_breakingImpulseThreshold; - int m_isEnabled; - }; - - -// -------------------------------------------------- // - class btTypedConstraintData - { - public: - bInvalidHandle *m_rbA; - bInvalidHandle *m_rbB; - char *m_name; - int m_objectType; - int m_userConstraintType; - int m_userConstraintId; - int m_needsFeedback; - float m_appliedImpulse; - float m_dbgDrawSize; - int m_disableCollisionsBetweenLinkedBodies; - int m_overrideNumSolverIterations; - float m_breakingImpulseThreshold; - int m_isEnabled; - }; - - -// -------------------------------------------------- // - class btTypedConstraintDoubleData - { - public: - btRigidBodyDoubleData *m_rbA; - btRigidBodyDoubleData *m_rbB; - char *m_name; - int m_objectType; - int m_userConstraintType; - int m_userConstraintId; - int m_needsFeedback; - double m_appliedImpulse; - double m_dbgDrawSize; - int m_disableCollisionsBetweenLinkedBodies; - int m_overrideNumSolverIterations; - double m_breakingImpulseThreshold; - int m_isEnabled; - char padding[4]; - }; - - -// -------------------------------------------------- // - class btPoint2PointConstraintFloatData - { - public: - btTypedConstraintData m_typeConstraintData; - btVector3FloatData m_pivotInA; - btVector3FloatData m_pivotInB; - }; - - -// -------------------------------------------------- // - class btPoint2PointConstraintDoubleData2 - { - public: - btTypedConstraintDoubleData m_typeConstraintData; - btVector3DoubleData m_pivotInA; - btVector3DoubleData m_pivotInB; - }; - - -// -------------------------------------------------- // - class btPoint2PointConstraintDoubleData - { - public: - btTypedConstraintData m_typeConstraintData; - btVector3DoubleData m_pivotInA; - btVector3DoubleData m_pivotInB; - }; - - -// -------------------------------------------------- // - class btHingeConstraintDoubleData - { - public: - btTypedConstraintData m_typeConstraintData; - btTransformDoubleData m_rbAFrame; - btTransformDoubleData m_rbBFrame; - int m_useReferenceFrameA; - int m_angularOnly; - int m_enableAngularMotor; - float m_motorTargetVelocity; - float m_maxMotorImpulse; - float m_lowerLimit; - float m_upperLimit; - float m_limitSoftness; - float m_biasFactor; - float m_relaxationFactor; - }; - - -// -------------------------------------------------- // - class btHingeConstraintFloatData - { - public: - btTypedConstraintData m_typeConstraintData; - btTransformFloatData m_rbAFrame; - btTransformFloatData m_rbBFrame; - int m_useReferenceFrameA; - int m_angularOnly; - int m_enableAngularMotor; - float m_motorTargetVelocity; - float m_maxMotorImpulse; - float m_lowerLimit; - float m_upperLimit; - float m_limitSoftness; - float m_biasFactor; - float m_relaxationFactor; - }; - - -// -------------------------------------------------- // - class btHingeConstraintDoubleData2 - { - public: - btTypedConstraintDoubleData m_typeConstraintData; - btTransformDoubleData m_rbAFrame; - btTransformDoubleData m_rbBFrame; - int m_useReferenceFrameA; - int m_angularOnly; - int m_enableAngularMotor; - double m_motorTargetVelocity; - double m_maxMotorImpulse; - double m_lowerLimit; - double m_upperLimit; - double m_limitSoftness; - double m_biasFactor; - double m_relaxationFactor; - char m_padding1[4]; - }; - - -// -------------------------------------------------- // - class btConeTwistConstraintDoubleData - { - public: - btTypedConstraintDoubleData m_typeConstraintData; - btTransformDoubleData m_rbAFrame; - btTransformDoubleData m_rbBFrame; - double m_swingSpan1; - double m_swingSpan2; - double m_twistSpan; - double m_limitSoftness; - double m_biasFactor; - double m_relaxationFactor; - double m_damping; - }; - - -// -------------------------------------------------- // - class btConeTwistConstraintData - { - public: - btTypedConstraintData m_typeConstraintData; - btTransformFloatData m_rbAFrame; - btTransformFloatData m_rbBFrame; - float m_swingSpan1; - float m_swingSpan2; - float m_twistSpan; - float m_limitSoftness; - float m_biasFactor; - float m_relaxationFactor; - float m_damping; - char m_pad[4]; - }; - - -// -------------------------------------------------- // - class btGeneric6DofConstraintData - { - public: - btTypedConstraintData m_typeConstraintData; - btTransformFloatData m_rbAFrame; - btTransformFloatData m_rbBFrame; - btVector3FloatData m_linearUpperLimit; - btVector3FloatData m_linearLowerLimit; - btVector3FloatData m_angularUpperLimit; - btVector3FloatData m_angularLowerLimit; - int m_useLinearReferenceFrameA; - int m_useOffsetForConstraintFrame; - }; - - -// -------------------------------------------------- // - class btGeneric6DofConstraintDoubleData2 - { - public: - btTypedConstraintDoubleData m_typeConstraintData; - btTransformDoubleData m_rbAFrame; - btTransformDoubleData m_rbBFrame; - btVector3DoubleData m_linearUpperLimit; - btVector3DoubleData m_linearLowerLimit; - btVector3DoubleData m_angularUpperLimit; - btVector3DoubleData m_angularLowerLimit; - int m_useLinearReferenceFrameA; - int m_useOffsetForConstraintFrame; - }; - - -// -------------------------------------------------- // - class btGeneric6DofSpringConstraintData - { - public: - btGeneric6DofConstraintData m_6dofData; - int m_springEnabled[6]; - float m_equilibriumPoint[6]; - float m_springStiffness[6]; - float m_springDamping[6]; - }; - - -// -------------------------------------------------- // - class btGeneric6DofSpringConstraintDoubleData2 - { - public: - btGeneric6DofConstraintDoubleData2 m_6dofData; - int m_springEnabled[6]; - double m_equilibriumPoint[6]; - double m_springStiffness[6]; - double m_springDamping[6]; - }; - - -// -------------------------------------------------- // - class btGeneric6DofSpring2ConstraintData - { - public: - btTypedConstraintData m_typeConstraintData; - btTransformFloatData m_rbAFrame; - btTransformFloatData m_rbBFrame; - btVector3FloatData m_linearUpperLimit; - btVector3FloatData m_linearLowerLimit; - btVector3FloatData m_linearBounce; - btVector3FloatData m_linearStopERP; - btVector3FloatData m_linearStopCFM; - btVector3FloatData m_linearMotorERP; - btVector3FloatData m_linearMotorCFM; - btVector3FloatData m_linearTargetVelocity; - btVector3FloatData m_linearMaxMotorForce; - btVector3FloatData m_linearServoTarget; - btVector3FloatData m_linearSpringStiffness; - btVector3FloatData m_linearSpringDamping; - btVector3FloatData m_linearEquilibriumPoint; - char m_linearEnableMotor[4]; - char m_linearServoMotor[4]; - char m_linearEnableSpring[4]; - char m_linearSpringStiffnessLimited[4]; - char m_linearSpringDampingLimited[4]; - char m_padding1[4]; - btVector3FloatData m_angularUpperLimit; - btVector3FloatData m_angularLowerLimit; - btVector3FloatData m_angularBounce; - btVector3FloatData m_angularStopERP; - btVector3FloatData m_angularStopCFM; - btVector3FloatData m_angularMotorERP; - btVector3FloatData m_angularMotorCFM; - btVector3FloatData m_angularTargetVelocity; - btVector3FloatData m_angularMaxMotorForce; - btVector3FloatData m_angularServoTarget; - btVector3FloatData m_angularSpringStiffness; - btVector3FloatData m_angularSpringDamping; - btVector3FloatData m_angularEquilibriumPoint; - char m_angularEnableMotor[4]; - char m_angularServoMotor[4]; - char m_angularEnableSpring[4]; - char m_angularSpringStiffnessLimited[4]; - char m_angularSpringDampingLimited[4]; - int m_rotateOrder; - }; - - -// -------------------------------------------------- // - class btGeneric6DofSpring2ConstraintDoubleData2 - { - public: - btTypedConstraintDoubleData m_typeConstraintData; - btTransformDoubleData m_rbAFrame; - btTransformDoubleData m_rbBFrame; - btVector3DoubleData m_linearUpperLimit; - btVector3DoubleData m_linearLowerLimit; - btVector3DoubleData m_linearBounce; - btVector3DoubleData m_linearStopERP; - btVector3DoubleData m_linearStopCFM; - btVector3DoubleData m_linearMotorERP; - btVector3DoubleData m_linearMotorCFM; - btVector3DoubleData m_linearTargetVelocity; - btVector3DoubleData m_linearMaxMotorForce; - btVector3DoubleData m_linearServoTarget; - btVector3DoubleData m_linearSpringStiffness; - btVector3DoubleData m_linearSpringDamping; - btVector3DoubleData m_linearEquilibriumPoint; - char m_linearEnableMotor[4]; - char m_linearServoMotor[4]; - char m_linearEnableSpring[4]; - char m_linearSpringStiffnessLimited[4]; - char m_linearSpringDampingLimited[4]; - char m_padding1[4]; - btVector3DoubleData m_angularUpperLimit; - btVector3DoubleData m_angularLowerLimit; - btVector3DoubleData m_angularBounce; - btVector3DoubleData m_angularStopERP; - btVector3DoubleData m_angularStopCFM; - btVector3DoubleData m_angularMotorERP; - btVector3DoubleData m_angularMotorCFM; - btVector3DoubleData m_angularTargetVelocity; - btVector3DoubleData m_angularMaxMotorForce; - btVector3DoubleData m_angularServoTarget; - btVector3DoubleData m_angularSpringStiffness; - btVector3DoubleData m_angularSpringDamping; - btVector3DoubleData m_angularEquilibriumPoint; - char m_angularEnableMotor[4]; - char m_angularServoMotor[4]; - char m_angularEnableSpring[4]; - char m_angularSpringStiffnessLimited[4]; - char m_angularSpringDampingLimited[4]; - int m_rotateOrder; - }; - - -// -------------------------------------------------- // - class btSliderConstraintData - { - public: - btTypedConstraintData m_typeConstraintData; - btTransformFloatData m_rbAFrame; - btTransformFloatData m_rbBFrame; - float m_linearUpperLimit; - float m_linearLowerLimit; - float m_angularUpperLimit; - float m_angularLowerLimit; - int m_useLinearReferenceFrameA; - int m_useOffsetForConstraintFrame; - }; - - -// -------------------------------------------------- // - class btSliderConstraintDoubleData - { - public: - btTypedConstraintDoubleData m_typeConstraintData; - btTransformDoubleData m_rbAFrame; - btTransformDoubleData m_rbBFrame; - double m_linearUpperLimit; - double m_linearLowerLimit; - double m_angularUpperLimit; - double m_angularLowerLimit; - int m_useLinearReferenceFrameA; - int m_useOffsetForConstraintFrame; - }; - - -// -------------------------------------------------- // - class btGearConstraintFloatData - { - public: - btTypedConstraintFloatData m_typeConstraintData; - btVector3FloatData m_axisInA; - btVector3FloatData m_axisInB; - float m_ratio; - char m_padding[4]; - }; - - -// -------------------------------------------------- // - class btGearConstraintDoubleData - { - public: - btTypedConstraintDoubleData m_typeConstraintData; - btVector3DoubleData m_axisInA; - btVector3DoubleData m_axisInB; - double m_ratio; - }; - - -// -------------------------------------------------- // - class SoftBodyMaterialData - { - public: - float m_linearStiffness; - float m_angularStiffness; - float m_volumeStiffness; - int m_flags; - }; - - -// -------------------------------------------------- // - class SoftBodyNodeData - { - public: - SoftBodyMaterialData *m_material; - btVector3FloatData m_position; - btVector3FloatData m_previousPosition; - btVector3FloatData m_velocity; - btVector3FloatData m_accumulatedForce; - btVector3FloatData m_normal; - float m_inverseMass; - float m_area; - int m_attach; - int m_pad; - }; - - -// -------------------------------------------------- // - class SoftBodyLinkData - { - public: - SoftBodyMaterialData *m_material; - int m_nodeIndices[2]; - float m_restLength; - int m_bbending; - }; - - -// -------------------------------------------------- // - class SoftBodyFaceData - { - public: - btVector3FloatData m_normal; - SoftBodyMaterialData *m_material; - int m_nodeIndices[3]; - float m_restArea; - }; - - -// -------------------------------------------------- // - class SoftBodyTetraData - { - public: - btVector3FloatData m_c0[4]; - SoftBodyMaterialData *m_material; - int m_nodeIndices[4]; - float m_restVolume; - float m_c1; - float m_c2; - int m_pad; - }; - - -// -------------------------------------------------- // - class SoftRigidAnchorData - { - public: - btMatrix3x3FloatData m_c0; - btVector3FloatData m_c1; - btVector3FloatData m_localFrame; - bInvalidHandle *m_rigidBody; - int m_nodeIndex; - float m_c2; - }; - - -// -------------------------------------------------- // - class SoftBodyConfigData - { - public: - int m_aeroModel; - float m_baumgarte; - float m_damping; - float m_drag; - float m_lift; - float m_pressure; - float m_volume; - float m_dynamicFriction; - float m_poseMatch; - float m_rigidContactHardness; - float m_kineticContactHardness; - float m_softContactHardness; - float m_anchorHardness; - float m_softRigidClusterHardness; - float m_softKineticClusterHardness; - float m_softSoftClusterHardness; - float m_softRigidClusterImpulseSplit; - float m_softKineticClusterImpulseSplit; - float m_softSoftClusterImpulseSplit; - float m_maxVolume; - float m_timeScale; - int m_velocityIterations; - int m_positionIterations; - int m_driftIterations; - int m_clusterIterations; - int m_collisionFlags; - }; - - -// -------------------------------------------------- // - class SoftBodyPoseData - { - public: - btMatrix3x3FloatData m_rot; - btMatrix3x3FloatData m_scale; - btMatrix3x3FloatData m_aqq; - btVector3FloatData m_com; - btVector3FloatData *m_positions; - float *m_weights; - int m_numPositions; - int m_numWeigts; - int m_bvolume; - int m_bframe; - float m_restVolume; - int m_pad; - }; - - -// -------------------------------------------------- // - class SoftBodyClusterData - { - public: - btTransformFloatData m_framexform; - btMatrix3x3FloatData m_locii; - btMatrix3x3FloatData m_invwi; - btVector3FloatData m_com; - btVector3FloatData m_vimpulses[2]; - btVector3FloatData m_dimpulses[2]; - btVector3FloatData m_lv; - btVector3FloatData m_av; - btVector3FloatData *m_framerefs; - int *m_nodeIndices; - float *m_masses; - int m_numFrameRefs; - int m_numNodes; - int m_numMasses; - float m_idmass; - float m_imass; - int m_nvimpulses; - int m_ndimpulses; - float m_ndamping; - float m_ldamping; - float m_adamping; - float m_matching; - float m_maxSelfCollisionImpulse; - float m_selfCollisionImpulseFactor; - int m_containsAnchor; - int m_collide; - int m_clusterIndex; - }; - - -// -------------------------------------------------- // - class btSoftBodyJointData - { - public: - void *m_bodyA; - void *m_bodyB; - btVector3FloatData m_refs[2]; - float m_cfm; - float m_erp; - float m_split; - int m_delete; - btVector3FloatData m_relPosition[2]; - int m_bodyAtype; - int m_bodyBtype; - int m_jointType; - int m_pad; - }; - - -// -------------------------------------------------- // - class btSoftBodyFloatData - { - public: - btCollisionObjectFloatData m_collisionObjectData; - SoftBodyPoseData *m_pose; - SoftBodyMaterialData **m_materials; - SoftBodyNodeData *m_nodes; - SoftBodyLinkData *m_links; - SoftBodyFaceData *m_faces; - SoftBodyTetraData *m_tetrahedra; - SoftRigidAnchorData *m_anchors; - SoftBodyClusterData *m_clusters; - btSoftBodyJointData *m_joints; - int m_numMaterials; - int m_numNodes; - int m_numLinks; - int m_numFaces; - int m_numTetrahedra; - int m_numAnchors; - int m_numClusters; - int m_numJoints; - SoftBodyConfigData m_config; - }; - - -// -------------------------------------------------- // - class btMultiBodyLinkDoubleData - { - public: - btQuaternionDoubleData m_zeroRotParentToThis; - btVector3DoubleData m_parentComToThisPivotOffset; - btVector3DoubleData m_thisPivotToThisComOffset; - btVector3DoubleData m_jointAxisTop[6]; - btVector3DoubleData m_jointAxisBottom[6]; - btVector3DoubleData m_linkInertia; - btVector3DoubleData m_absFrameTotVelocityTop; - btVector3DoubleData m_absFrameTotVelocityBottom; - btVector3DoubleData m_absFrameLocVelocityTop; - btVector3DoubleData m_absFrameLocVelocityBottom; - double m_linkMass; - int m_parentIndex; - int m_jointType; - int m_dofCount; - int m_posVarCount; - double m_jointPos[7]; - double m_jointVel[6]; - double m_jointTorque[6]; - double m_jointDamping; - double m_jointFriction; - double m_jointLowerLimit; - double m_jointUpperLimit; - double m_jointMaxForce; - double m_jointMaxVelocity; - char *m_linkName; - char *m_jointName; - btCollisionObjectDoubleData *m_linkCollider; - char *m_paddingPtr; - }; - - -// -------------------------------------------------- // - class btMultiBodyLinkFloatData - { - public: - btQuaternionFloatData m_zeroRotParentToThis; - btVector3FloatData m_parentComToThisPivotOffset; - btVector3FloatData m_thisPivotToThisComOffset; - btVector3FloatData m_jointAxisTop[6]; - btVector3FloatData m_jointAxisBottom[6]; - btVector3FloatData m_linkInertia; - btVector3FloatData m_absFrameTotVelocityTop; - btVector3FloatData m_absFrameTotVelocityBottom; - btVector3FloatData m_absFrameLocVelocityTop; - btVector3FloatData m_absFrameLocVelocityBottom; - int m_dofCount; - float m_linkMass; - int m_parentIndex; - int m_jointType; - float m_jointPos[7]; - float m_jointVel[6]; - float m_jointTorque[6]; - int m_posVarCount; - float m_jointDamping; - float m_jointFriction; - float m_jointLowerLimit; - float m_jointUpperLimit; - float m_jointMaxForce; - float m_jointMaxVelocity; - char *m_linkName; - char *m_jointName; - btCollisionObjectFloatData *m_linkCollider; - char *m_paddingPtr; - }; - - -// -------------------------------------------------- // - class btMultiBodyDoubleData - { - public: - btVector3DoubleData m_baseWorldPosition; - btQuaternionDoubleData m_baseWorldOrientation; - btVector3DoubleData m_baseLinearVelocity; - btVector3DoubleData m_baseAngularVelocity; - btVector3DoubleData m_baseInertia; - double m_baseMass; - int m_numLinks; - char m_padding[4]; - char *m_baseName; - btMultiBodyLinkDoubleData *m_links; - btCollisionObjectDoubleData *m_baseCollider; - }; - - -// -------------------------------------------------- // - class btMultiBodyFloatData - { - public: - btVector3FloatData m_baseWorldPosition; - btQuaternionFloatData m_baseWorldOrientation; - btVector3FloatData m_baseLinearVelocity; - btVector3FloatData m_baseAngularVelocity; - btVector3FloatData m_baseInertia; - float m_baseMass; - int m_numLinks; - char *m_baseName; - btMultiBodyLinkFloatData *m_links; - btCollisionObjectFloatData *m_baseCollider; - }; - - -// -------------------------------------------------- // - class btMultiBodyLinkColliderFloatData - { - public: - btCollisionObjectFloatData m_colObjData; - btMultiBodyFloatData *m_multiBody; - int m_link; - char m_padding[4]; - }; - - -// -------------------------------------------------- // - class btMultiBodyLinkColliderDoubleData - { - public: - btCollisionObjectDoubleData m_colObjData; - btMultiBodyDoubleData *m_multiBody; - int m_link; - char m_padding[4]; - }; - - -} -#endif//__BULLET_H__ \ No newline at end of file diff --git a/extern/bullet/src/Extras/Serialize/BulletFileLoader/bChunk.cpp b/extern/bullet/src/Extras/Serialize/BulletFileLoader/bChunk.cpp deleted file mode 100644 index 564e5507e722..000000000000 --- a/extern/bullet/src/Extras/Serialize/BulletFileLoader/bChunk.cpp +++ /dev/null @@ -1,75 +0,0 @@ -/* -bParse -Copyright (c) 2006-2009 Charlie C & Erwin Coumans http://gamekit.googlecode.com - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#include "bChunk.h" -#include "bDefines.h" -#include "bFile.h" - -#if !defined( __CELLOS_LV2__) && !defined(__MWERKS__) -#include -#endif -#include - - -using namespace bParse; - - -// ----------------------------------------------------- // -short ChunkUtils::swapShort(short sht) -{ - SWITCH_SHORT(sht); - return sht; -} - -// ----------------------------------------------------- // -int ChunkUtils::swapInt(int inte) -{ - SWITCH_INT(inte); - return inte; -} - -// ----------------------------------------------------- // -long64 ChunkUtils::swapLong64(long64 lng) -{ - SWITCH_LONGINT(lng); - return lng; -} - -// ----------------------------------------------------- // -int ChunkUtils::getOffset(int flags) -{ - // if the file is saved in a - // different format, get the - // file's chunk size - int res = CHUNK_HEADER_LEN; - - if (VOID_IS_8) - { - if (flags &FD_BITS_VARIES) - res = sizeof(bChunkPtr4); - } - else - { - if (flags &FD_BITS_VARIES) - res = sizeof(bChunkPtr8); - } - return res; -} - - - - - -//eof diff --git a/extern/bullet/src/Extras/Serialize/BulletFileLoader/bChunk.h b/extern/bullet/src/Extras/Serialize/BulletFileLoader/bChunk.h deleted file mode 100644 index 77039bcf951a..000000000000 --- a/extern/bullet/src/Extras/Serialize/BulletFileLoader/bChunk.h +++ /dev/null @@ -1,92 +0,0 @@ -/* -bParse -Copyright (c) 2006-2009 Charlie C & Erwin Coumans http://gamekit.googlecode.com - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#ifndef __BCHUNK_H__ -#define __BCHUNK_H__ - -#if defined (_WIN32) && ! defined (__MINGW32__) - #define long64 __int64 -#elif defined (__MINGW32__) - #include - #define long64 int64_t -#else - #define long64 long long -#endif - - -namespace bParse { - - - // ----------------------------------------------------- // - class bChunkPtr4 - { - public: - bChunkPtr4(){} - int code; - int len; - union - { - int m_uniqueInt; - }; - int dna_nr; - int nr; - }; - - // ----------------------------------------------------- // - class bChunkPtr8 - { - public: - bChunkPtr8(){} - int code, len; - union - { - long64 oldPrev; - int m_uniqueInts[2]; - }; - int dna_nr, nr; - }; - - // ----------------------------------------------------- // - class bChunkInd - { - public: - bChunkInd(){} - int code, len; - void *oldPtr; - int dna_nr, nr; - }; - - - // ----------------------------------------------------- // - class ChunkUtils - { - public: - - // file chunk offset - static int getOffset(int flags); - - // endian utils - static short swapShort(short sht); - static int swapInt(int inte); - static long64 swapLong64(long64 lng); - - }; - - - const int CHUNK_HEADER_LEN = ((sizeof(bChunkInd))); - const bool VOID_IS_8 = ((sizeof(void*)==8)); -} - -#endif//__BCHUNK_H__ diff --git a/extern/bullet/src/Extras/Serialize/BulletFileLoader/bCommon.h b/extern/bullet/src/Extras/Serialize/BulletFileLoader/bCommon.h deleted file mode 100644 index b01d2b8992fd..000000000000 --- a/extern/bullet/src/Extras/Serialize/BulletFileLoader/bCommon.h +++ /dev/null @@ -1,39 +0,0 @@ -/* -bParse -Copyright (c) 2006-2009 Charlie C & Erwin Coumans http://gamekit.googlecode.com - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#ifndef __BCOMMON_H__ -#define __BCOMMON_H__ - - -#include -//#include "bLog.h" -#include "LinearMath/btAlignedObjectArray.h" -#include "LinearMath/btHashMap.h" - -namespace bParse { - - class bMain; - class bFileData; - class bFile; - class bDNA; - - // delete void* undefined - typedef struct bStructHandle {int unused;}bStructHandle; - typedef btAlignedObjectArray bListBasePtr; - typedef btHashMap bPtrMap; -} - - -#endif//__BCOMMON_H__ diff --git a/extern/bullet/src/Extras/Serialize/BulletFileLoader/bDNA.cpp b/extern/bullet/src/Extras/Serialize/BulletFileLoader/bDNA.cpp deleted file mode 100644 index 7b42062b3438..000000000000 --- a/extern/bullet/src/Extras/Serialize/BulletFileLoader/bDNA.cpp +++ /dev/null @@ -1,629 +0,0 @@ -/* -bParse -Copyright (c) 2006-2009 Charlie C & Erwin Coumans http://gamekit.googlecode.com - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ -#include - -#include "bDNA.h" -#include "bChunk.h" -#include -#include -#include - -//this define will force traversal of structures, to check backward (and forward) compatibility -//#define TEST_BACKWARD_FORWARD_COMPATIBILITY - - -using namespace bParse; - - -// ----------------------------------------------------- // -bDNA::bDNA() - : mPtrLen(0) -{ - // -- -} - -// ----------------------------------------------------- // -bDNA::~bDNA() -{ - // -- -} - -// ----------------------------------------------------- // -bool bDNA::lessThan(bDNA *file) -{ - return ( m_Names.size() < file->m_Names.size()); -} - -// ----------------------------------------------------- // -char *bDNA::getName(int ind) -{ - assert(ind <= (int)m_Names.size()); - return m_Names[ind].m_name; -} - - -// ----------------------------------------------------- // -char *bDNA::getType(int ind) -{ - assert(ind<= (int)mTypes.size()); - return mTypes[ind]; -} - - -// ----------------------------------------------------- // -short *bDNA::getStruct(int ind) -{ - assert(ind <= (int)mStructs.size()); - return mStructs[ind]; -} - - -// ----------------------------------------------------- // -short bDNA::getLength(int ind) -{ - assert(ind <= (int)mTlens.size()); - return mTlens[ind]; -} - - -// ----------------------------------------------------- // -int bDNA::getReverseType(short type) -{ - - int* intPtr = mStructReverse.find(type); - if (intPtr) - return *intPtr; - - return -1; -} - -// ----------------------------------------------------- // -int bDNA::getReverseType(const char *type) -{ - - btHashString key(type); - int* valuePtr = mTypeLookup.find(key); - if (valuePtr) - return *valuePtr; - - return -1; -} - -// ----------------------------------------------------- // -int bDNA::getNumStructs() -{ - return (int)mStructs.size(); -} - -// ----------------------------------------------------- // -bool bDNA::flagNotEqual(int dna_nr) -{ - assert(dna_nr <= (int)mCMPFlags.size()); - return mCMPFlags[dna_nr] == FDF_STRUCT_NEQU; -} - -// ----------------------------------------------------- // -bool bDNA::flagEqual(int dna_nr) -{ - assert(dna_nr <= (int)mCMPFlags.size()); - int flag = mCMPFlags[dna_nr]; - return flag == FDF_STRUCT_EQU; -} - -// ----------------------------------------------------- // -bool bDNA::flagNone(int dna_nr) -{ - assert(dna_nr <= (int)mCMPFlags.size()); - return mCMPFlags[dna_nr] == FDF_NONE; -} - -// ----------------------------------------------------- // -int bDNA::getPointerSize() -{ - return mPtrLen; -} - -// ----------------------------------------------------- // -void bDNA::initRecurseCmpFlags(int iter) -{ - // iter is FDF_STRUCT_NEQU - - short *oldStrc = mStructs[iter]; - short type = oldStrc[0]; - - for (int i=0; i<(int)mStructs.size(); i++) - { - if (i != iter && mCMPFlags[i] == FDF_STRUCT_EQU ) - { - short *curStruct = mStructs[i]; - int eleLen = curStruct[1]; - curStruct+=2; - - for (int j=0; jgetReverseType(typeName); - if (newLookup == -1) - { - mCMPFlags[i] = FDF_NONE; - continue; - } - short *curStruct = memDNA->mStructs[newLookup]; -#else - // memory for file - - if (oldLookup < memDNA->mStructs.size()) - { - short *curStruct = memDNA->mStructs[oldLookup]; -#endif - - - - // rebuild... - mCMPFlags[i] = FDF_STRUCT_NEQU; - -#ifndef TEST_BACKWARD_FORWARD_COMPATIBILITY - - if (curStruct[1] == oldStruct[1]) - { - // type len same ... - if (mTlens[oldStruct[0]] == memDNA->mTlens[curStruct[0]]) - { - bool isSame = true; - int elementLength = oldStruct[1]; - - - curStruct+=2; - oldStruct+=2; - - - for (int j=0; jmTypes[curStruct[0]])!=0) - { - isSame=false; - break; - } - - // name the same - if (strcmp(m_Names[oldStruct[1]].m_name, memDNA->m_Names[curStruct[1]].m_name)!=0) - { - isSame=false; - break; - } - } - // flag valid == - if (isSame) - mCMPFlags[i] = FDF_STRUCT_EQU; - } - } -#endif - } - } - - - - - - // recurse in - for ( i=0; i<(int)mStructs.size(); i++) - { - if (mCMPFlags[i] == FDF_STRUCT_NEQU) - initRecurseCmpFlags(i); - } -} - - - - -static int name_is_array(char* name, int* dim1, int* dim2) { - int len = strlen(name); - /*fprintf(stderr,"[%s]",name);*/ - /*if (len >= 1) { - if (name[len-1] != ']') - return 1; - } - return 0;*/ - char *bp; - int num; - if (dim1) { - *dim1 = 1; - } - if (dim2) { - *dim2 = 1; - } - bp = strchr(name, '['); - if (!bp) { - return 0; - } - num = 0; - while (++bp < name+len-1) { - const char c = *bp; - if (c == ']') { - break; - } - if (c <= '9' && c >= '0') { - num *= 10; - num += (c - '0'); - } else { - printf("array parse error.\n"); - return 0; - } - } - if (dim2) { - *dim2 = num; - } - - /* find second dim, if any. */ - bp = strchr(bp, '['); - if (!bp) { - return 1; /* at least we got the first dim. */ - } - num = 0; - while (++bp < name+len-1) { - const char c = *bp; - if (c == ']') { - break; - } - if (c <= '9' && c >= '0') { - num *= 10; - num += (c - '0'); - } else { - printf("array2 parse error.\n"); - return 1; - } - } - if (dim1) { - if (dim2) { - *dim1 = *dim2; - *dim2 = num; - } else { - *dim1 = num; - } - } - - return 1; -} - - -// ----------------------------------------------------- // -void bDNA::init(char *data, int len, bool swap) -{ - int *intPtr=0;short *shtPtr=0; - char *cp = 0;int dataLen =0; - //long nr=0; - intPtr = (int*)data; - - /* - SDNA (4 bytes) (magic number) - NAME (4 bytes) - (4 bytes) amount of names (int) - - - */ - - if (strncmp(data, "SDNA", 4)==0) - { - // skip ++ NAME - intPtr++; intPtr++; - } - - - - // Parse names - if (swap) - { - *intPtr = ChunkUtils::swapInt(*intPtr); - } - dataLen = *intPtr; - intPtr++; - - cp = (char*)intPtr; - int i; - for ( i=0; i amount of types (int) - - - */ - - intPtr = (int*)cp; - assert(strncmp(cp, "TYPE", 4)==0); intPtr++; - - if (swap) - { - *intPtr = ChunkUtils::swapInt(*intPtr); - } - dataLen = *intPtr; - intPtr++; - - cp = (char*)intPtr; - for ( i=0; i (short) the lengths of types - - */ - - // Parse type lens - intPtr = (int*)cp; - assert(strncmp(cp, "TLEN", 4)==0); intPtr++; - - dataLen = (int)mTypes.size(); - - shtPtr = (short*)intPtr; - for ( i=0; i amount of structs (int) - - - - - - - */ - - intPtr = (int*)shtPtr; - cp = (char*)intPtr; - assert(strncmp(cp, "STRC", 4)==0); intPtr++; - - if (swap) - { - *intPtr = ChunkUtils::swapInt(*intPtr); - } - dataLen = *intPtr; - intPtr++; - - - shtPtr = (short*)intPtr; - for ( i=0; itypes_count; ++i) { - /* if (!bf->types[i].is_struct)*/ - { - printf("%3d: sizeof(%s%s)=%d", - i, - bf->types[i].is_struct ? "struct " : "atomic ", - bf->types[i].name, bf->types[i].size); - if (bf->types[i].is_struct) { - int j; - printf(", %d fields: { ", bf->types[i].fieldtypes_count); - for (j=0; jtypes[i].fieldtypes_count; ++j) { - printf("%s %s", - bf->types[bf->types[i].fieldtypes[j]].name, - bf->names[bf->types[i].fieldnames[j]]); - if (j == bf->types[i].fieldtypes_count-1) { - printf(";}"); - } else { - printf("; "); - } - } - } - printf("\n\n"); - - } - } -#endif - -} - - - - -//eof - - diff --git a/extern/bullet/src/Extras/Serialize/BulletFileLoader/bDNA.h b/extern/bullet/src/Extras/Serialize/BulletFileLoader/bDNA.h deleted file mode 100644 index 691080bf54ce..000000000000 --- a/extern/bullet/src/Extras/Serialize/BulletFileLoader/bDNA.h +++ /dev/null @@ -1,110 +0,0 @@ -/* -bParse -Copyright (c) 2006-2009 Charlie C & Erwin Coumans http://gamekit.googlecode.com - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#ifndef __BDNA_H__ -#define __BDNA_H__ - - -#include "bCommon.h" - -namespace bParse { - - struct bNameInfo - { - char* m_name; - bool m_isPointer; - int m_dim0; - int m_dim1; - }; - - class bDNA - { - public: - bDNA(); - ~bDNA(); - - void init(char *data, int len, bool swap=false); - - int getArraySize(char* str); - int getArraySizeNew(short name) - { - const bNameInfo& nameInfo = m_Names[name]; - return nameInfo.m_dim0*nameInfo.m_dim1; - } - int getElementSize(short type, short name) - { - const bNameInfo& nameInfo = m_Names[name]; - int size = nameInfo.m_isPointer ? mPtrLen*nameInfo.m_dim0*nameInfo.m_dim1 : mTlens[type]*nameInfo.m_dim0*nameInfo.m_dim1; - return size; - } - - int getNumNames() const - { - return m_Names.size(); - } - - char *getName(int ind); - char *getType(int ind); - short *getStruct(int ind); - short getLength(int ind); - int getReverseType(short type); - int getReverseType(const char *type); - - - int getNumStructs(); - - // - bool lessThan(bDNA* other); - - void initCmpFlags(bDNA *memDNA); - bool flagNotEqual(int dna_nr); - bool flagEqual(int dna_nr); - bool flagNone(int dna_nr); - - - int getPointerSize(); - - void dumpTypeDefinitions(); - - - private: - enum FileDNAFlags - { - FDF_NONE=0, - FDF_STRUCT_NEQU, - FDF_STRUCT_EQU - }; - - void initRecurseCmpFlags(int i); - - btAlignedObjectArray mCMPFlags; - - btAlignedObjectArray m_Names; - btAlignedObjectArray mTypes; - btAlignedObjectArray mStructs; - btAlignedObjectArray mTlens; - btHashMap mStructReverse; - btHashMap mTypeLookup; - - int mPtrLen; - - - - - }; -} - - -#endif//__BDNA_H__ diff --git a/extern/bullet/src/Extras/Serialize/BulletFileLoader/bDefines.h b/extern/bullet/src/Extras/Serialize/BulletFileLoader/bDefines.h deleted file mode 100644 index 3a9e2c987f4e..000000000000 --- a/extern/bullet/src/Extras/Serialize/BulletFileLoader/bDefines.h +++ /dev/null @@ -1,139 +0,0 @@ -/* Copyright (C) 2006-2009 Charlie C & Erwin Coumans http://gamekit.googlecode.com -* -* This software is provided 'as-is', without any express or implied -* warranty. In no event will the authors be held liable for any damages -* arising from the use of this software. -* -* Permission is granted to anyone to use this software for any purpose, -* including commercial applications, and to alter it and redistribute it -* freely, subject to the following restrictions: -* -* 1. The origin of this software must not be misrepresented; you must not -* claim that you wrote the original software. If you use this software -* in a product, an acknowledgment in the product documentation would be -* appreciated but is not required. -* 2. Altered source versions must be plainly marked as such, and must not be -* misrepresented as being the original software. -* 3. This notice may not be removed or altered from any source distribution. -*/ -#ifndef __B_DEFINES_H__ -#define __B_DEFINES_H__ - - -// MISC defines, see BKE_global.h, BKE_utildefines.h -#define SIZEOFBLENDERHEADER 12 - - -// ------------------------------------------------------------ -#if defined(__sgi) || defined (__sparc) || defined (__sparc__) || defined (__PPC__) || defined (__ppc__) || defined (__BIG_ENDIAN__) -# define MAKE_ID(a,b,c,d) ( (int)(a)<<24 | (int)(b)<<16 | (c)<<8 | (d) ) -#else -# define MAKE_ID(a,b,c,d) ( (int)(d)<<24 | (int)(c)<<16 | (b)<<8 | (a) ) -#endif - - -// ------------------------------------------------------------ -#if defined(__sgi) || defined(__sparc) || defined(__sparc__) || defined (__PPC__) || defined (__ppc__) || defined (__BIG_ENDIAN__) -# define MAKE_ID2(c, d) ( (c)<<8 | (d) ) -# define MOST_SIG_BYTE 0 -# define BBIG_ENDIAN -#else -# define MAKE_ID2(c, d) ( (d)<<8 | (c) ) -# define MOST_SIG_BYTE 1 -# define BLITTLE_ENDIAN -#endif - -// ------------------------------------------------------------ -#define ID_SCE MAKE_ID2('S', 'C') -#define ID_LI MAKE_ID2('L', 'I') -#define ID_OB MAKE_ID2('O', 'B') -#define ID_ME MAKE_ID2('M', 'E') -#define ID_CU MAKE_ID2('C', 'U') -#define ID_MB MAKE_ID2('M', 'B') -#define ID_MA MAKE_ID2('M', 'A') -#define ID_TE MAKE_ID2('T', 'E') -#define ID_IM MAKE_ID2('I', 'M') -#define ID_IK MAKE_ID2('I', 'K') -#define ID_WV MAKE_ID2('W', 'V') -#define ID_LT MAKE_ID2('L', 'T') -#define ID_SE MAKE_ID2('S', 'E') -#define ID_LF MAKE_ID2('L', 'F') -#define ID_LA MAKE_ID2('L', 'A') -#define ID_CA MAKE_ID2('C', 'A') -#define ID_IP MAKE_ID2('I', 'P') -#define ID_KE MAKE_ID2('K', 'E') -#define ID_WO MAKE_ID2('W', 'O') -#define ID_SCR MAKE_ID2('S', 'R') -#define ID_VF MAKE_ID2('V', 'F') -#define ID_TXT MAKE_ID2('T', 'X') -#define ID_SO MAKE_ID2('S', 'O') -#define ID_SAMPLE MAKE_ID2('S', 'A') -#define ID_GR MAKE_ID2('G', 'R') -#define ID_ID MAKE_ID2('I', 'D') -#define ID_AR MAKE_ID2('A', 'R') -#define ID_AC MAKE_ID2('A', 'C') -#define ID_SCRIPT MAKE_ID2('P', 'Y') -#define ID_FLUIDSIM MAKE_ID2('F', 'S') -#define ID_NT MAKE_ID2('N', 'T') -#define ID_BR MAKE_ID2('B', 'R') - - -#define ID_SEQ MAKE_ID2('S', 'Q') -#define ID_CO MAKE_ID2('C', 'O') -#define ID_PO MAKE_ID2('A', 'C') -#define ID_NLA MAKE_ID2('N', 'L') - -#define ID_VS MAKE_ID2('V', 'S') -#define ID_VN MAKE_ID2('V', 'N') - - -// ------------------------------------------------------------ -#define FORM MAKE_ID('F','O','R','M') -#define DDG1 MAKE_ID('3','D','G','1') -#define DDG2 MAKE_ID('3','D','G','2') -#define DDG3 MAKE_ID('3','D','G','3') -#define DDG4 MAKE_ID('3','D','G','4') -#define GOUR MAKE_ID('G','O','U','R') -#define BLEN MAKE_ID('B','L','E','N') -#define DER_ MAKE_ID('D','E','R','_') -#define V100 MAKE_ID('V','1','0','0') -#define DATA MAKE_ID('D','A','T','A') -#define GLOB MAKE_ID('G','L','O','B') -#define IMAG MAKE_ID('I','M','A','G') -#define USER MAKE_ID('U','S','E','R') - - -// ------------------------------------------------------------ -#define DNA1 MAKE_ID('D','N','A','1') -#define REND MAKE_ID('R','E','N','D') -#define ENDB MAKE_ID('E','N','D','B') -#define NAME MAKE_ID('N','A','M','E') -#define SDNA MAKE_ID('S','D','N','A') -#define TYPE MAKE_ID('T','Y','P','E') -#define TLEN MAKE_ID('T','L','E','N') -#define STRC MAKE_ID('S','T','R','C') - - -// ------------------------------------------------------------ -#define SWITCH_INT(a) { \ - char s_i, *p_i; \ - p_i= (char *)&(a); \ - s_i=p_i[0]; p_i[0]=p_i[3]; p_i[3]=s_i; \ - s_i=p_i[1]; p_i[1]=p_i[2]; p_i[2]=s_i; } - -// ------------------------------------------------------------ -#define SWITCH_SHORT(a) { \ - char s_i, *p_i; \ - p_i= (char *)&(a); \ - s_i=p_i[0]; p_i[0]=p_i[1]; p_i[1]=s_i; } - -// ------------------------------------------------------------ -#define SWITCH_LONGINT(a) { \ - char s_i, *p_i; \ - p_i= (char *)&(a); \ - s_i=p_i[0]; p_i[0]=p_i[7]; p_i[7]=s_i; \ - s_i=p_i[1]; p_i[1]=p_i[6]; p_i[6]=s_i; \ - s_i=p_i[2]; p_i[2]=p_i[5]; p_i[5]=s_i; \ - s_i=p_i[3]; p_i[3]=p_i[4]; p_i[4]=s_i; } - -#endif//__B_DEFINES_H__ diff --git a/extern/bullet/src/Extras/Serialize/BulletFileLoader/bFile.cpp b/extern/bullet/src/Extras/Serialize/BulletFileLoader/bFile.cpp deleted file mode 100644 index 69a503e79a47..000000000000 --- a/extern/bullet/src/Extras/Serialize/BulletFileLoader/bFile.cpp +++ /dev/null @@ -1,1773 +0,0 @@ -/* -bParse -Copyright (c) 2006-2009 Charlie C & Erwin Coumans http://gamekit.googlecode.com - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ -#include "bFile.h" -#include "bCommon.h" -#include "bChunk.h" -#include "bDNA.h" -#include -#include -#include -#include "bDefines.h" -#include "LinearMath/btSerializer.h" -#include "LinearMath/btAlignedAllocator.h" -#include "LinearMath/btMinMax.h" - -#define SIZEOFBLENDERHEADER 12 -#define MAX_ARRAY_LENGTH 512 -using namespace bParse; -#define MAX_STRLEN 1024 - -const char* getCleanName(const char* memName, char* buffer) -{ - int slen = strlen(memName); - assert(sleninit will convert part of DNA file endianness to current CPU endianness if necessary - mFileDNA->init((char*)dnaBuffer, dnaLen, (mFlags & FD_ENDIAN_SWAP)!=0); - - if (verboseMode & FD_VERBOSE_DUMP_DNA_TYPE_DEFINITIONS) - mFileDNA->dumpTypeDefinitions(); -} - -// ----------------------------------------------------- // -void bFile::parseInternal(int verboseMode, char* memDna,int memDnaLength) -{ - if ( (mFlags &FD_OK) ==0) - return; - - if (mFlags & FD_FILEDNA_IS_MEMDNA) - { - setFileDNA(verboseMode,memDna,memDnaLength); - } - - if (mFileDNA==0) - { - char *blenderData = mFileBuffer; - bChunkInd dna; - dna.oldPtr = 0; - - char *tempBuffer = blenderData; - for (int i=0; i 0) - { - if (strncmp((tempBuffer + ChunkUtils::getOffset(mFlags)), "SDNANAME", 8) ==0) - dna.oldPtr = (tempBuffer + ChunkUtils::getOffset(mFlags)); - else dna.oldPtr = 0; - } - else dna.oldPtr = 0; - } - // Some Bullet files are missing the DNA1 block - // In Blender it's DNA1 + ChunkUtils::getOffset() + SDNA + NAME - // In Bullet tests its SDNA + NAME - else if (strncmp(tempBuffer, "SDNANAME", 8) ==0) - { - dna.oldPtr = blenderData + i; - dna.len = mFileLen-i; - - // Also no REND block, so exit now. - if (mVersion==276) break; - } - - if (mDataStart && dna.oldPtr) break; - tempBuffer++; - } - if (!dna.oldPtr || !dna.len) - { - //printf("Failed to find DNA1+SDNA pair\n"); - mFlags &= ~FD_OK; - return; - } - - - mFileDNA = new bDNA(); - - - ///mFileDNA->init will convert part of DNA file endianness to current CPU endianness if necessary - mFileDNA->init((char*)dna.oldPtr, dna.len, (mFlags & FD_ENDIAN_SWAP)!=0); - - - if (mVersion==276) - { - int i; - for (i=0;igetNumNames();i++) - { - if (strcmp(mFileDNA->getName(i),"int")==0) - { - mFlags |= FD_BROKEN_DNA; - } - } - if ((mFlags&FD_BROKEN_DNA)!=0) - { - //printf("warning: fixing some broken DNA version\n"); - } - } - - - - if (verboseMode & FD_VERBOSE_DUMP_DNA_TYPE_DEFINITIONS) - mFileDNA->dumpTypeDefinitions(); - } - mMemoryDNA = new bDNA(); - int littleEndian= 1; - littleEndian= ((char*)&littleEndian)[0]; - - mMemoryDNA->init(memDna,memDnaLength,littleEndian==0); - - - - - ///@todo we need a better version check, add version/sub version info from FileGlobal into memory DNA/header files - if (mMemoryDNA->getNumNames() != mFileDNA->getNumNames()) - { - mFlags |= FD_VERSION_VARIES; - //printf ("Warning, file DNA is different than built in, performance is reduced. Best to re-export file with a matching version/platform"); - } - - // as long as it kept up to date it will be ok!! - if (mMemoryDNA->lessThan(mFileDNA)) - { - //printf ("Warning, file DNA is newer than built in."); - } - - - mFileDNA->initCmpFlags(mMemoryDNA); - - parseData(); - - resolvePointers(verboseMode); - - updateOldPointers(); - - -} - - - -// ----------------------------------------------------- // -void bFile::swap(char *head, bChunkInd& dataChunk, bool ignoreEndianFlag) -{ - char *data = head; - short *strc = mFileDNA->getStruct(dataChunk.dna_nr); - - - - const char s[] = "SoftBodyMaterialData"; - int szs = sizeof(s); - if (strncmp((char*)&dataChunk.code,"ARAY",4)==0) - { - short *oldStruct = mFileDNA->getStruct(dataChunk.dna_nr); - char *oldType = mFileDNA->getType(oldStruct[0]); - if (strncmp(oldType,s,szs)==0) - { - return; - } - } - - - int len = mFileDNA->getLength(strc[0]); - - for (int i=0; icode & 0xFFFF)==0) - c->code >>=16; - SWITCH_INT(c->len); - SWITCH_INT(c->dna_nr); - SWITCH_INT(c->nr); - } else - { - bChunkPtr8* c = (bChunkPtr8*) dataPtr; - if ((c->code & 0xFFFF)==0) - c->code >>=16; - SWITCH_INT(c->len); - SWITCH_INT(c->dna_nr); - SWITCH_INT(c->nr); - - } - } else - { - if (mFlags &FD_BITS_VARIES) - { - bChunkPtr8*c = (bChunkPtr8*) dataPtr; - if ((c->code & 0xFFFF)==0) - c->code >>=16; - SWITCH_INT(c->len); - SWITCH_INT(c->dna_nr); - SWITCH_INT(c->nr); - - } else - { - bChunkPtr4* c = (bChunkPtr4*) dataPtr; - if ((c->code & 0xFFFF)==0) - c->code >>=16; - SWITCH_INT(c->len); - - SWITCH_INT(c->dna_nr); - SWITCH_INT(c->nr); - - } - } - -} - - -void bFile::swapDNA(char* ptr) -{ - bool swap = ((mFlags & FD_ENDIAN_SWAP)!=0); - - int offset = (mFlags & FD_FILE_64)? 24 : 20; - char* data = &ptr[offset]; - -// void bDNA::init(char *data, int len, bool swap) - int *intPtr=0;short *shtPtr=0; - char *cp = 0;int dataLen =0; - intPtr = (int*)data; - - /* - SDNA (4 bytes) (magic number) - NAME (4 bytes) - (4 bytes) amount of names (int) - - - */ - - if (strncmp(data, "SDNA", 4)==0) - { - // skip ++ NAME - intPtr++; - intPtr++; - } else - { - - if (strncmp(data+4, "SDNA", 4)==0) - { - // skip ++ NAME - intPtr++; - intPtr++; - intPtr++; - } - } - - - - - // Parse names - if (swap) - dataLen = ChunkUtils::swapInt(*intPtr); - else - dataLen = *intPtr; - - *intPtr = ChunkUtils::swapInt(*intPtr); - intPtr++; - - cp = (char*)intPtr; - int i; - for ( i=0; i amount of types (int) - - - */ - - intPtr = (int*)cp; - assert(strncmp(cp, "TYPE", 4)==0); intPtr++; - - if (swap) - dataLen = ChunkUtils::swapInt(*intPtr); - else - dataLen = *intPtr; - - *intPtr = ChunkUtils::swapInt(*intPtr); - - intPtr++; - - cp = (char*)intPtr; - for ( i=0; i (short) the lengths of types - - */ - - // Parse type lens - intPtr = (int*)cp; - assert(strncmp(cp, "TLEN", 4)==0); intPtr++; - - - shtPtr = (short*)intPtr; - for ( i=0; i amount of structs (int) - - - - - - - */ - - intPtr = (int*)shtPtr; - cp = (char*)intPtr; - assert(strncmp(cp, "STRC", 4)==0); - intPtr++; - - if (swap) - dataLen = ChunkUtils::swapInt(*intPtr); - else - dataLen = *intPtr; - - *intPtr = ChunkUtils::swapInt(*intPtr); - - intPtr++; - - - shtPtr = (short*)intPtr; - for ( i=0; i=0) - { - swap(dataPtrHead, dataChunk,ignoreEndianFlag); - } else - { - //printf("unknown chunk\n"); - } - } - - // next please! - dataPtr += seek; - - seek = getNextBlock(&dataChunk, dataPtr, mFlags); - if (seek < 0) - break; - } - - if (mFlags & FD_ENDIAN_SWAP) - { - mFlags &= ~FD_ENDIAN_SWAP; - } else - { - mFlags |= FD_ENDIAN_SWAP; - } - - - -} - - -// ----------------------------------------------------- // -char* bFile::readStruct(char *head, bChunkInd& dataChunk) -{ - bool ignoreEndianFlag = false; - - if (mFlags & FD_ENDIAN_SWAP) - swap(head, dataChunk, ignoreEndianFlag); - - - - if (!mFileDNA->flagEqual(dataChunk.dna_nr)) - { - // Ouch! need to rebuild the struct - short *oldStruct,*curStruct; - char *oldType, *newType; - int oldLen, curLen, reverseOld; - - - oldStruct = mFileDNA->getStruct(dataChunk.dna_nr); - oldType = mFileDNA->getType(oldStruct[0]); - - oldLen = mFileDNA->getLength(oldStruct[0]); - - if ((mFlags&FD_BROKEN_DNA)!=0) - { - if ((strcmp(oldType,"btQuantizedBvhNodeData")==0)&&oldLen==20) - { - return 0; - } - if ((strcmp(oldType,"btShortIntIndexData")==0)) - { - int allocLen = 2; - char *dataAlloc = new char[(dataChunk.nr*allocLen)+1]; - memset(dataAlloc, 0, (dataChunk.nr*allocLen)+1); - short* dest = (short*) dataAlloc; - const short* src = (short*) head; - for (int i=0;igetReverseType(oldType); - - if ((reverseOld!=-1)) - { - // make sure it's here - //assert(reverseOld!= -1 && "getReverseType() returned -1, struct required!"); - - // - curStruct = mMemoryDNA->getStruct(reverseOld); - newType = mMemoryDNA->getType(curStruct[0]); - curLen = mMemoryDNA->getLength(curStruct[0]); - - - - // make sure it's the same - assert((strcmp(oldType, newType)==0) && "internal error, struct mismatch!"); - - - numallocs++; - // numBlocks * length - - int allocLen = (curLen); - char *dataAlloc = new char[(dataChunk.nr*allocLen)+1]; - memset(dataAlloc, 0, (dataChunk.nr*allocLen)); - - // track allocated - addDataBlock(dataAlloc); - - char *cur = dataAlloc; - char *old = head; - for (int block=0; blockgetStruct(dataChunk.dna_nr); - oldType = mFileDNA->getType(oldStruct[0]); - printf("%s equal structure, just memcpy\n",oldType); -#endif // - } - - - char *dataAlloc = new char[(dataChunk.len)+1]; - memset(dataAlloc, 0, dataChunk.len+1); - - - // track allocated - addDataBlock(dataAlloc); - - memcpy(dataAlloc, head, dataChunk.len); - return dataAlloc; - -} - - -// ----------------------------------------------------- // -void bFile::parseStruct(char *strcPtr, char *dtPtr, int old_dna, int new_dna, bool fixupPointers) -{ - if (old_dna == -1) return; - if (new_dna == -1) return; - - //disable this, because we need to fixup pointers/ListBase - if (0)//mFileDNA->flagEqual(old_dna)) - { - short *strc = mFileDNA->getStruct(old_dna); - int len = mFileDNA->getLength(strc[0]); - - memcpy(strcPtr, dtPtr, len); - return; - } - - // Ok, now build the struct - char *memType, *memName, *cpc, *cpo; - short *fileStruct, *filePtrOld, *memoryStruct, *firstStruct; - int elementLength, size, revType, old_nr, new_nr, fpLen; - short firstStructType; - - - // File to memory lookup - memoryStruct = mMemoryDNA->getStruct(new_dna); - fileStruct = mFileDNA->getStruct(old_dna); - firstStruct = fileStruct; - - - filePtrOld = fileStruct; - firstStructType = mMemoryDNA->getStruct(0)[0]; - - // Get number of elements - elementLength = memoryStruct[1]; - memoryStruct+=2; - - cpc = strcPtr; cpo = 0; - for (int ele=0; elegetType(memoryStruct[0]); - memName = mMemoryDNA->getName(memoryStruct[1]); - - - size = mMemoryDNA->getElementSize(memoryStruct[0], memoryStruct[1]); - revType = mMemoryDNA->getReverseType(memoryStruct[0]); - - if (revType != -1 && memoryStruct[0]>=firstStructType && memName[0] != '*') - { - cpo = getFileElement(firstStruct, memName, memType, dtPtr, &filePtrOld); - if (cpo) - { - int arrayLen = mFileDNA->getArraySizeNew(filePtrOld[1]); - old_nr = mFileDNA->getReverseType(memType); - new_nr = revType; - fpLen = mFileDNA->getElementSize(filePtrOld[0], filePtrOld[1]); - if (arrayLen==1) - { - parseStruct(cpc, cpo, old_nr, new_nr,fixupPointers); - } else - { - char* tmpCpc = cpc; - char* tmpCpo = cpo; - - for (int i=0;i3 && type <8) - { - char c; - char *cp = data; - for (int i=0; igetPointerSize(); - int ptrMem = mMemoryDNA->getPointerSize(); - - if (!src && !dst) - return; - - - if (ptrFile == ptrMem) - { - memcpy(dst, src, ptrMem); - } - else if (ptrMem==4 && ptrFile==8) - { - btPointerUid* oldPtr = (btPointerUid*)src; - btPointerUid* newPtr = (btPointerUid*)dst; - - if (oldPtr->m_uniqueIds[0] == oldPtr->m_uniqueIds[1]) - { - //Bullet stores the 32bit unique ID in both upper and lower part of 64bit pointers - //so it can be used to distinguish between .blend and .bullet - newPtr->m_uniqueIds[0] = oldPtr->m_uniqueIds[0]; - } else - { - //deal with pointers the Blender .blend style way, see - //readfile.c in the Blender source tree - long64 longValue = *((long64*)src); - //endian swap for 64bit pointer otherwise truncation will fail due to trailing zeros - if (mFlags & FD_ENDIAN_SWAP) - SWITCH_LONGINT(longValue); - *((int*)dst) = (int)(longValue>>3); - } - - } - else if (ptrMem==8 && ptrFile==4) - { - btPointerUid* oldPtr = (btPointerUid*)src; - btPointerUid* newPtr = (btPointerUid*)dst; - if (oldPtr->m_uniqueIds[0] == oldPtr->m_uniqueIds[1]) - { - newPtr->m_uniqueIds[0] = oldPtr->m_uniqueIds[0]; - newPtr->m_uniqueIds[1] = 0; - } else - { - *((long64*)dst)= *((int*)src); - } - } - else - { - printf ("%d %d\n", ptrFile,ptrMem); - assert(0 && "Invalid pointer len"); - } - - -} - - -// ----------------------------------------------------- // -void bFile::getMatchingFileDNA(short* dna_addr, const char* lookupName, const char* lookupType, char *strcData, char *data, bool fixupPointers) -{ - // find the matching memory dna data - // to the file being loaded. Fill the - // memory with the file data... - - int len = dna_addr[1]; - dna_addr+=2; - - for (int i=0; igetType(dna_addr[0]); - const char* name = mFileDNA->getName(dna_addr[1]); - - - - int eleLen = mFileDNA->getElementSize(dna_addr[0], dna_addr[1]); - - if ((mFlags&FD_BROKEN_DNA)!=0) - { - if ((strcmp(type,"short")==0)&&(strcmp(name,"int")==0)) - { - eleLen = 0; - } - } - - if (strcmp(lookupName, name)==0) - { - //int arrayLenold = mFileDNA->getArraySize((char*)name.c_str()); - int arrayLen = mFileDNA->getArraySizeNew(dna_addr[1]); - //assert(arrayLenold == arrayLen); - - if (name[0] == '*') - { - // cast pointers - int ptrFile = mFileDNA->getPointerSize(); - int ptrMem = mMemoryDNA->getPointerSize(); - safeSwapPtr(strcData,data); - - if (fixupPointers) - { - if (arrayLen > 1) - { - //void **sarray = (void**)strcData; - //void **darray = (void**)data; - - char *cpc, *cpo; - cpc = (char*)strcData; - cpo = (char*)data; - - for (int a=0; agetStruct(old_nr); - int elementLength = old[1]; - old+=2; - - for (int i=0; igetType(old[0]); - char* name = mFileDNA->getName(old[1]); - int len = mFileDNA->getElementSize(old[0], old[1]); - - if (strcmp(lookupName, name)==0) - { - if (strcmp(type, lookupType)==0) - { - if (foundPos) - *foundPos = old; - return data; - } - return 0; - } - data+=len; - } - return 0; -} - - -// ----------------------------------------------------- // -void bFile::swapStruct(int dna_nr, char *data,bool ignoreEndianFlag) -{ - if (dna_nr == -1) return; - - short *strc = mFileDNA->getStruct(dna_nr); - //short *firstStrc = strc; - - int elementLen= strc[1]; - strc+=2; - - short first = mFileDNA->getStruct(0)[0]; - - char *buf = data; - for (int i=0; igetType(strc[0]); - char *name = mFileDNA->getName(strc[1]); - - int size = mFileDNA->getElementSize(strc[0], strc[1]); - if (strc[0] >= first && name[0]!='*') - { - int old_nr = mFileDNA->getReverseType(type); - int arrayLen = mFileDNA->getArraySizeNew(strc[1]); - if (arrayLen==1) - { - swapStruct(old_nr,buf,ignoreEndianFlag); - } else - { - char* tmpBuf = buf; - for (int i=0;igetArraySize(name); - int arrayLen = mFileDNA->getArraySizeNew(strc[1]); - //assert(arrayLenOld == arrayLen); - swapData(buf, strc[0], arrayLen,ignoreEndianFlag); - } - buf+=size; - } -} - -void bFile::resolvePointersMismatch() -{ -// printf("resolvePointersStructMismatch\n"); - - int i; - - for (i=0;i< m_pointerFixupArray.size();i++) - { - char* cur = m_pointerFixupArray.at(i); - void** ptrptr = (void**) cur; - void* ptr = *ptrptr; - ptr = findLibPointer(ptr); - if (ptr) - { - //printf("Fixup pointer!\n"); - *(ptrptr) = ptr; - } else - { -// printf("pointer not found: %x\n",cur); - } - } - - - for (i=0; igetPointerSize(); - int ptrFile = mFileDNA->getPointerSize(); - - - int blockLen = block->len / ptrFile; - - void *onptr = findLibPointer(*ptrptr); - if (onptr) - { - char *newPtr = new char[blockLen * ptrMem]; - addDataBlock(newPtr); - memset(newPtr, 0, blockLen * ptrMem); - - void **onarray = (void**)onptr; - char *oldPtr = (char*)onarray; - - int p = 0; - while (blockLen-- > 0) - { - btPointerUid dp = {{0}}; - safeSwapPtr((char*)dp.m_uniqueIds, oldPtr); - - void **tptr = (void**)(newPtr + p * ptrMem); - *tptr = findLibPointer(dp.m_ptr); - - oldPtr += ptrFile; - ++p; - } - - *ptrptr = newPtr; - } - } - } -} - - -///this loop only works fine if the Blender DNA structure of the file matches the headerfiles -void bFile::resolvePointersChunk(const bChunkInd& dataChunk, int verboseMode) -{ - bParse::bDNA* fileDna = mFileDNA ? mFileDNA : mMemoryDNA; - - short int* oldStruct = fileDna->getStruct(dataChunk.dna_nr); - short oldLen = fileDna->getLength(oldStruct[0]); - //char* structType = fileDna->getType(oldStruct[0]); - - char* cur = (char*)findLibPointer(dataChunk.oldPtr); - for (int block=0; blockgetStruct(0)[0]; - - - char* elemPtr= strcPtr; - - short int* oldStruct = fileDna->getStruct(dna_nr); - - int elementLength = oldStruct[1]; - oldStruct+=2; - - int totalSize = 0; - - for (int ele=0; elegetType(oldStruct[0]); - memName = fileDna->getName(oldStruct[1]); - - - - int arrayLen = fileDna->getArraySizeNew(oldStruct[1]); - if (memName[0] == '*') - { - if (arrayLen > 1) - { - void **array= (void**)elemPtr; - for (int a=0; a ",&memName[1]); - printf("%p ", array[a]); - printf("\n",&memName[1]); - } - - array[a] = findLibPointer(array[a]); - } - } - else - { - void** ptrptr = (void**) elemPtr; - void* ptr = *ptrptr; - if (verboseMode & FD_VERBOSE_EXPORT_XML) - { - for (int i=0;i ",&memName[1]); - printf("%p ", ptr); - printf("\n",&memName[1]); - } - ptr = findLibPointer(ptr); - - if (ptr) - { - // printf("Fixup pointer at 0x%x from 0x%x to 0x%x!\n",ptrptr,*ptrptr,ptr); - *(ptrptr) = ptr; - if (memName[1] == '*' && ptrptr && *ptrptr) - { - // This will only work if the given **array is continuous - void **array= (void**)*(ptrptr); - void *np= array[0]; - int n=0; - while (np) - { - np= findLibPointer(array[n]); - if (np) array[n]= np; - n++; - } - } - } else - { - // printf("Cannot fixup pointer at 0x%x from 0x%x to 0x%x!\n",ptrptr,*ptrptr,ptr); - } - } - } else - { - int revType = fileDna->getReverseType(oldStruct[0]); - if (oldStruct[0]>=firstStructType) //revType != -1 && - { - char cleanName[MAX_STRLEN]; - getCleanName(memName,cleanName); - - int arrayLen = fileDna->getArraySizeNew(oldStruct[1]); - int byteOffset = 0; - - if (verboseMode & FD_VERBOSE_EXPORT_XML) - { - for (int i=0;i1) - { - printf("<%s type=\"%s\" count=%d>\n",cleanName,memType, arrayLen); - } else - { - printf("<%s type=\"%s\">\n",cleanName,memType); - } - } - - for (int i=0;i\n",cleanName); - } - } else - { - //export a simple type - if (verboseMode & FD_VERBOSE_EXPORT_XML) - { - - if (arrayLen>MAX_ARRAY_LENGTH) - { - printf("too long\n"); - } else - { - //printf("%s %s\n",memType,memName); - - bool isIntegerType = (strcmp(memType,"char")==0) || (strcmp(memType,"int")==0) || (strcmp(memType,"short")==0); - - if (isIntegerType) - { - const char* newtype="int"; - int dbarray[MAX_ARRAY_LENGTH]; - int* dbPtr = 0; - char* tmp = elemPtr; - dbPtr = &dbarray[0]; - if (dbPtr) - { - char cleanName[MAX_STRLEN]; - getCleanName(memName,cleanName); - - int i; - getElement(arrayLen, newtype,memType, tmp, (char*)dbPtr); - for (i=0;i",cleanName,memType); - else - printf("<%s type=\"%s\" count=%d>",cleanName,memType,arrayLen); - for (i=0;i\n",cleanName); - } - } else - { - const char* newtype="double"; - double dbarray[MAX_ARRAY_LENGTH]; - double* dbPtr = 0; - char* tmp = elemPtr; - dbPtr = &dbarray[0]; - if (dbPtr) - { - int i; - getElement(arrayLen, newtype,memType, tmp, (char*)dbPtr); - for (i=0;i",memName,memType); - } - else - { - printf("<%s type=\"%s\" count=%d>",cleanName,memType,arrayLen); - } - for (i=0;i\n",cleanName); - } - } - } - - } - } - } - - int size = fileDna->getElementSize(oldStruct[0], oldStruct[1]); - totalSize += size; - elemPtr+=size; - - } - - return totalSize; -} - - -///Resolve pointers replaces the original pointers in structures, and linked lists by the new in-memory structures -void bFile::resolvePointers(int verboseMode) -{ - bParse::bDNA* fileDna = mFileDNA ? mFileDNA : mMemoryDNA; - - //char *dataPtr = mFileBuffer+mDataStart; - - if (1) //mFlags & (FD_BITS_VARIES | FD_VERSION_VARIES)) - { - resolvePointersMismatch(); - } - - { - - if (verboseMode & FD_VERBOSE_EXPORT_XML) - { - printf("\n"); - int numitems = m_chunks.size(); - printf("\n", btGetVersion(), numitems); - } - for (int i=0;iflagEqual(dataChunk.dna_nr)) - { - //dataChunk.len - short int* oldStruct = fileDna->getStruct(dataChunk.dna_nr); - char* oldType = fileDna->getType(oldStruct[0]); - - if (verboseMode & FD_VERBOSE_EXPORT_XML) - printf(" <%s pointer=%p>\n",oldType,dataChunk.oldPtr); - - resolvePointersChunk(dataChunk, verboseMode); - - if (verboseMode & FD_VERBOSE_EXPORT_XML) - printf(" \n",oldType); - } else - { - //printf("skipping mStruct\n"); - } - } - if (verboseMode & FD_VERBOSE_EXPORT_XML) - { - printf("\n"); - } - } - - -} - - -// ----------------------------------------------------- // -void* bFile::findLibPointer(void *ptr) -{ - - bStructHandle** ptrptr = getLibPointers().find(ptr); - if (ptrptr) - return *ptrptr; - return 0; -} - - -void bFile::updateOldPointers() -{ - int i; - - for (i=0;igetStruct(dataChunk.dna_nr); - char* typeName = dna->getType(newStruct[0]); - printf("%3d: %s ",i,typeName); - - printf("code=%s ",codestr); - - printf("ptr=%p ",dataChunk.oldPtr); - printf("len=%d ",dataChunk.len); - printf("nr=%d ",dataChunk.nr); - if (dataChunk.nr!=1) - { - printf("not 1\n"); - } - printf("\n"); - - - - - } - -#if 0 - IDFinderData ifd; - ifd.success = 0; - ifd.IDname = NULL; - ifd.just_print_it = 1; - for (i=0; im_blocks.size(); ++i) - { - BlendBlock* bb = bf->m_blocks[i]; - printf("tag='%s'\tptr=%p\ttype=%s\t[%4d]", bb->tag, bb,bf->types[bb->type_index].name,bb->m_array_entries_.size()); - block_ID_finder(bb, bf, &ifd); - printf("\n"); - } -#endif - -} - - -void bFile::writeChunks(FILE* fp, bool fixupPointers) -{ - bParse::bDNA* fileDna = mFileDNA ? mFileDNA : mMemoryDNA; - - for (int i=0;igetStruct(dataChunk.dna_nr); - oldType = fileDna->getType(oldStruct[0]); - //int oldLen = fileDna->getLength(oldStruct[0]); - ///don't try to convert Link block data, just memcpy it. Other data can be converted. - reverseOld = mMemoryDNA->getReverseType(oldType); - - - if ((reverseOld!=-1)) - { - // make sure it's here - //assert(reverseOld!= -1 && "getReverseType() returned -1, struct required!"); - // - curStruct = mMemoryDNA->getStruct(reverseOld); - newType = mMemoryDNA->getType(curStruct[0]); - // make sure it's the same - assert((strcmp(oldType, newType)==0) && "internal error, struct mismatch!"); - - - curLen = mMemoryDNA->getLength(curStruct[0]); - dataChunk.dna_nr = reverseOld; - if (strcmp("Link",oldType)!=0) - { - dataChunk.len = curLen * dataChunk.nr; - } else - { -// printf("keep length of link = %d\n",dataChunk.len); - } - - //write the structure header - fwrite(&dataChunk,sizeof(bChunkInd),1,fp); - - - - short int* curStruct1; - curStruct1 = mMemoryDNA->getStruct(dataChunk.dna_nr); - assert(curStruct1 == curStruct); - - char* cur = fixupPointers ? (char*)findLibPointer(dataChunk.oldPtr) : (char*)dataChunk.oldPtr; - - //write the actual contents of the structure(s) - fwrite(cur,dataChunk.len,1,fp); - } else - { - printf("serious error, struct mismatch: don't write\n"); - } - } - -} - - -// ----------------------------------------------------- // -int bFile::getNextBlock(bChunkInd *dataChunk, const char *dataPtr, const int flags) -{ - bool swap = false; - bool varies = false; - - if (flags &FD_ENDIAN_SWAP) - swap = true; - if (flags &FD_BITS_VARIES) - varies = true; - - if (VOID_IS_8) - { - if (varies) - { - bChunkPtr4 head; - memcpy(&head, dataPtr, sizeof(bChunkPtr4)); - - - bChunkPtr8 chunk; - - chunk.code = head.code; - chunk.len = head.len; - chunk.m_uniqueInts[0] = head.m_uniqueInt; - chunk.m_uniqueInts[1] = 0; - chunk.dna_nr = head.dna_nr; - chunk.nr = head.nr; - - if (swap) - { - if ((chunk.code & 0xFFFF)==0) - chunk.code >>=16; - - SWITCH_INT(chunk.len); - SWITCH_INT(chunk.dna_nr); - SWITCH_INT(chunk.nr); - } - - - memcpy(dataChunk, &chunk, sizeof(bChunkInd)); - } - else - { - bChunkPtr8 c; - memcpy(&c, dataPtr, sizeof(bChunkPtr8)); - - if (swap) - { - if ((c.code & 0xFFFF)==0) - c.code >>=16; - - SWITCH_INT(c.len); - SWITCH_INT(c.dna_nr); - SWITCH_INT(c.nr); - } - - memcpy(dataChunk, &c, sizeof(bChunkInd)); - } - } - else - { - if (varies) - { - bChunkPtr8 head; - memcpy(&head, dataPtr, sizeof(bChunkPtr8)); - - - bChunkPtr4 chunk; - chunk.code = head.code; - chunk.len = head.len; - - if (head.m_uniqueInts[0]==head.m_uniqueInts[1]) - { - chunk.m_uniqueInt = head.m_uniqueInts[0]; - } else - { - long64 oldPtr =0; - memcpy(&oldPtr, &head.m_uniqueInts[0], 8); - if (swap) - SWITCH_LONGINT(oldPtr); - chunk.m_uniqueInt = (int)(oldPtr >> 3); - } - - - chunk.dna_nr = head.dna_nr; - chunk.nr = head.nr; - - if (swap) - { - if ((chunk.code & 0xFFFF)==0) - chunk.code >>=16; - - SWITCH_INT(chunk.len); - SWITCH_INT(chunk.dna_nr); - SWITCH_INT(chunk.nr); - } - - memcpy(dataChunk, &chunk, sizeof(bChunkInd)); - } - else - { - bChunkPtr4 c; - memcpy(&c, dataPtr, sizeof(bChunkPtr4)); - - if (swap) - { - if ((c.code & 0xFFFF)==0) - c.code >>=16; - - SWITCH_INT(c.len); - SWITCH_INT(c.dna_nr); - SWITCH_INT(c.nr); - } - memcpy(dataChunk, &c, sizeof(bChunkInd)); - } - } - - if (dataChunk->len < 0) - return -1; - -#if 0 - print ("----------"); - print (dataChunk->code); - print (dataChunk->len); - print (dataChunk->old); - print (dataChunk->dna_nr); - print (dataChunk->nr); -#endif - return (dataChunk->len+ChunkUtils::getOffset(flags)); -} - - - -//eof diff --git a/extern/bullet/src/Extras/Serialize/BulletFileLoader/bFile.h b/extern/bullet/src/Extras/Serialize/BulletFileLoader/bFile.h deleted file mode 100644 index e3523febb8fa..000000000000 --- a/extern/bullet/src/Extras/Serialize/BulletFileLoader/bFile.h +++ /dev/null @@ -1,175 +0,0 @@ -/* -bParse -Copyright (c) 2006-2009 Charlie C & Erwin Coumans http://gamekit.googlecode.com - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#ifndef __BFILE_H__ -#define __BFILE_H__ - -#include "bCommon.h" -#include "bChunk.h" -#include - -namespace bParse { - - // ----------------------------------------------------- // - enum bFileFlags - { - FD_INVALID =0, - FD_OK =1, - FD_VOID_IS_8 =2, - FD_ENDIAN_SWAP =4, - FD_FILE_64 =8, - FD_BITS_VARIES =16, - FD_VERSION_VARIES = 32, - FD_DOUBLE_PRECISION =64, - FD_BROKEN_DNA = 128, - FD_FILEDNA_IS_MEMDNA = 256 - }; - - enum bFileVerboseMode - { - FD_VERBOSE_EXPORT_XML = 1, - FD_VERBOSE_DUMP_DNA_TYPE_DEFINITIONS = 2, - FD_VERBOSE_DUMP_CHUNKS = 4, - FD_VERBOSE_DUMP_FILE_INFO=8, - }; - // ----------------------------------------------------- // - class bFile - { - protected: - - char m_headerString[7]; - - bool mOwnsBuffer; - char* mFileBuffer; - int mFileLen; - int mVersion; - - - bPtrMap mLibPointers; - - int mDataStart; - bDNA* mFileDNA; - bDNA* mMemoryDNA; - - btAlignedObjectArray m_pointerFixupArray; - btAlignedObjectArray m_pointerPtrFixupArray; - - btAlignedObjectArray m_chunks; - btHashMap m_chunkPtrPtrMap; - - // - - bPtrMap mDataPointers; - - - int mFlags; - - // //////////////////////////////////////////////////////////////////////////// - - // buffer offset util - int getNextBlock(bChunkInd *dataChunk, const char *dataPtr, const int flags); - void safeSwapPtr(char *dst, const char *src); - - virtual void parseHeader(); - - virtual void parseData() = 0; - - void resolvePointersMismatch(); - void resolvePointersChunk(const bChunkInd& dataChunk, int verboseMode); - - int resolvePointersStructRecursive(char *strcPtr, int old_dna, int verboseMode, int recursion); - //void swapPtr(char *dst, char *src); - - void parseStruct(char *strcPtr, char *dtPtr, int old_dna, int new_dna, bool fixupPointers); - void getMatchingFileDNA(short* old, const char* lookupName, const char* lookupType, char *strcData, char *data, bool fixupPointers); - char* getFileElement(short *firstStruct, char *lookupName, char *lookupType, char *data, short **foundPos); - - - void swap(char *head, class bChunkInd& ch, bool ignoreEndianFlag); - void swapData(char *data, short type, int arraySize, bool ignoreEndianFlag); - void swapStruct(int dna_nr, char *data, bool ignoreEndianFlag); - void swapLen(char *dataPtr); - void swapDNA(char* ptr); - - - char* readStruct(char *head, class bChunkInd& chunk); - char *getAsString(int code); - - virtual void parseInternal(int verboseMode, char* memDna,int memDnaLength); - - public: - bFile(const char *filename, const char headerString[7]); - - //todo: make memoryBuffer const char - //bFile( const char *memoryBuffer, int len); - bFile( char *memoryBuffer, int len, const char headerString[7]); - virtual ~bFile(); - - bDNA* getFileDNA() - { - return mFileDNA; - } - - virtual void addDataBlock(char* dataBlock) = 0; - - int getFlags() const - { - return mFlags; - } - - void setFileDNAisMemoryDNA() - { - mFlags |= FD_FILEDNA_IS_MEMDNA; - } - - bPtrMap& getLibPointers() - { - return mLibPointers; - } - - void* findLibPointer(void *ptr); - - bool ok(); - - virtual void parse(int verboseMode) = 0; - - virtual int write(const char* fileName, bool fixupPointers=false) = 0; - - virtual void writeChunks(FILE* fp, bool fixupPointers ); - - virtual void writeDNA(FILE* fp) = 0; - - void updateOldPointers(); - void resolvePointers(int verboseMode); - - void dumpChunks(bDNA* dna); - - virtual void setFileDNA(int verboseMode, char* buffer, int len); - - int getVersion() const - { - return mVersion; - } - //pre-swap the endianness, so that data loaded on a target with different endianness doesn't need to be swapped - void preSwap(); - void writeFile(const char* fileName); - - - - }; -} - - -#endif//__BFILE_H__ diff --git a/extern/bullet/src/Extras/Serialize/BulletFileLoader/btBulletFile.cpp b/extern/bullet/src/Extras/Serialize/BulletFileLoader/btBulletFile.cpp deleted file mode 100644 index 34333f38b974..000000000000 --- a/extern/bullet/src/Extras/Serialize/BulletFileLoader/btBulletFile.cpp +++ /dev/null @@ -1,448 +0,0 @@ -/* -bParse -Copyright (c) 2006-2010 Erwin Coumans http://gamekit.googlecode.com - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#include "btBulletFile.h" -#include "bDefines.h" -#include "bDNA.h" - -#if !defined( __CELLOS_LV2__) && !defined(__MWERKS__) -#include -#endif -#include - - -// 32 && 64 bit versions -#ifdef BT_INTERNAL_UPDATE_SERIALIZATION_STRUCTURES -#ifdef _WIN64 -extern char sBulletDNAstr64[]; -extern int sBulletDNAlen64; -#else -extern char sBulletDNAstr[]; -extern int sBulletDNAlen; -#endif //_WIN64 -#else//BT_INTERNAL_UPDATE_SERIALIZATION_STRUCTURES - -extern char sBulletDNAstr64[]; -extern int sBulletDNAlen64; -extern char sBulletDNAstr[]; -extern int sBulletDNAlen; - -#endif //BT_INTERNAL_UPDATE_SERIALIZATION_STRUCTURES - -using namespace bParse; - -btBulletFile::btBulletFile() -:bFile("", "BULLET ") -{ - mMemoryDNA = new bDNA(); //this memory gets released in the bFile::~bFile destructor,@todo not consistent with the rule 'who allocates it, has to deallocate it" - - m_DnaCopy = 0; - - -#ifdef BT_INTERNAL_UPDATE_SERIALIZATION_STRUCTURES -#ifdef _WIN64 - m_DnaCopy = (char*)btAlignedAlloc(sBulletDNAlen64,16); - memcpy(m_DnaCopy,sBulletDNAstr64,sBulletDNAlen64); - mMemoryDNA->init(m_DnaCopy,sBulletDNAlen64); -#else//_WIN64 - m_DnaCopy = (char*)btAlignedAlloc(sBulletDNAlen,16); - memcpy(m_DnaCopy,sBulletDNAstr,sBulletDNAlen); - mMemoryDNA->init(m_DnaCopy,sBulletDNAlen); -#endif//_WIN64 -#else//BT_INTERNAL_UPDATE_SERIALIZATION_STRUCTURES - if (VOID_IS_8) - { - m_DnaCopy = (char*) btAlignedAlloc(sBulletDNAlen64,16); - memcpy(m_DnaCopy,sBulletDNAstr64,sBulletDNAlen64); - mMemoryDNA->init(m_DnaCopy,sBulletDNAlen64); - } - else - { - m_DnaCopy =(char*) btAlignedAlloc(sBulletDNAlen,16); - memcpy(m_DnaCopy,sBulletDNAstr,sBulletDNAlen); - mMemoryDNA->init(m_DnaCopy,sBulletDNAlen); - } -#endif//BT_INTERNAL_UPDATE_SERIALIZATION_STRUCTURES -} - - - -btBulletFile::btBulletFile(const char* fileName) -:bFile(fileName, "BULLET ") -{ - m_DnaCopy = 0; -} - - - -btBulletFile::btBulletFile(char *memoryBuffer, int len) -:bFile(memoryBuffer,len, "BULLET ") -{ - m_DnaCopy = 0; -} - - -btBulletFile::~btBulletFile() -{ - if (m_DnaCopy) - btAlignedFree(m_DnaCopy); - - - while (m_dataBlocks.size()) - { - char* dataBlock = m_dataBlocks[m_dataBlocks.size()-1]; - delete[] dataBlock; - m_dataBlocks.pop_back(); - } - -} - - - -// ----------------------------------------------------- // -void btBulletFile::parseData() -{ -// printf ("Building datablocks"); -// printf ("Chunk size = %d",CHUNK_HEADER_LEN); -// printf ("File chunk size = %d",ChunkUtils::getOffset(mFlags)); - - const bool brokenDNA = (mFlags&FD_BROKEN_DNA)!=0; - - //const bool swap = (mFlags&FD_ENDIAN_SWAP)!=0; - - - int remain = mFileLen; - - mDataStart = 12; - remain-=12; - - //invalid/empty file? - if (remain < sizeof(bChunkInd)) - return; - - char *dataPtr = mFileBuffer+mDataStart; - - bChunkInd dataChunk; - dataChunk.code = 0; - - - //dataPtr += ChunkUtils::getNextBlock(&dataChunk, dataPtr, mFlags); - int seek = getNextBlock(&dataChunk, dataPtr, mFlags); - - - if (mFlags &FD_ENDIAN_SWAP) - swapLen(dataPtr); - - //dataPtr += ChunkUtils::getOffset(mFlags); - char *dataPtrHead = 0; - - while (dataChunk.code != DNA1) - { - if (!brokenDNA || (dataChunk.code != BT_QUANTIZED_BVH_CODE) ) - { - - // one behind - if (dataChunk.code == SDNA) break; - //if (dataChunk.code == DNA1) break; - - // same as (BHEAD+DATA dependency) - dataPtrHead = dataPtr+ChunkUtils::getOffset(mFlags); - if (dataChunk.dna_nr>=0) - { - char *id = readStruct(dataPtrHead, dataChunk); - - // lookup maps - if (id) - { - m_chunkPtrPtrMap.insert(dataChunk.oldPtr, dataChunk); - mLibPointers.insert(dataChunk.oldPtr, (bStructHandle*)id); - - m_chunks.push_back(dataChunk); - // block it - //bListBasePtr *listID = mMain->getListBasePtr(dataChunk.code); - //if (listID) - // listID->push_back((bStructHandle*)id); - } - - if (dataChunk.code == BT_CONTACTMANIFOLD_CODE) - { - m_contactManifolds.push_back((bStructHandle*)id); - } - if (dataChunk.code == BT_MULTIBODY_CODE) - { - m_multiBodies.push_back((bStructHandle*)id); - } - - if (dataChunk.code == BT_MB_LINKCOLLIDER_CODE) - { - m_multiBodyLinkColliders.push_back((bStructHandle*)id); - } - - if (dataChunk.code == BT_SOFTBODY_CODE) - { - m_softBodies.push_back((bStructHandle*) id); - } - - if (dataChunk.code == BT_RIGIDBODY_CODE) - { - m_rigidBodies.push_back((bStructHandle*) id); - } - - if (dataChunk.code == BT_DYNAMICSWORLD_CODE) - { - m_dynamicsWorldInfo.push_back((bStructHandle*) id); - } - - if (dataChunk.code == BT_CONSTRAINT_CODE) - { - m_constraints.push_back((bStructHandle*) id); - } - - if (dataChunk.code == BT_QUANTIZED_BVH_CODE) - { - m_bvhs.push_back((bStructHandle*) id); - } - - if (dataChunk.code == BT_TRIANLGE_INFO_MAP) - { - m_triangleInfoMaps.push_back((bStructHandle*) id); - } - - if (dataChunk.code == BT_COLLISIONOBJECT_CODE) - { - m_collisionObjects.push_back((bStructHandle*) id); - } - - if (dataChunk.code == BT_SHAPE_CODE) - { - m_collisionShapes.push_back((bStructHandle*) id); - } - - // if (dataChunk.code == GLOB) - // { - // m_glob = (bStructHandle*) id; - // } - } else - { - //printf("unknown chunk\n"); - - mLibPointers.insert(dataChunk.oldPtr, (bStructHandle*)dataPtrHead); - } - } else - { - printf("skipping BT_QUANTIZED_BVH_CODE due to broken DNA\n"); - } - - - dataPtr += seek; - remain-=seek; - if (remain<=0) - break; - - seek = getNextBlock(&dataChunk, dataPtr, mFlags); - if (mFlags &FD_ENDIAN_SWAP) - swapLen(dataPtr); - - if (seek < 0) - break; - } - -} - -void btBulletFile::addDataBlock(char* dataBlock) -{ - m_dataBlocks.push_back(dataBlock); - -} - - - - -void btBulletFile::writeDNA(FILE* fp) -{ - - bChunkInd dataChunk; - dataChunk.code = DNA1; - dataChunk.dna_nr = 0; - dataChunk.nr = 1; -#ifdef BT_INTERNAL_UPDATE_SERIALIZATION_STRUCTURES - if (VOID_IS_8) - { -#ifdef _WIN64 - dataChunk.len = sBulletDNAlen64; - dataChunk.oldPtr = sBulletDNAstr64; - fwrite(&dataChunk,sizeof(bChunkInd),1,fp); - fwrite(sBulletDNAstr64, sBulletDNAlen64,1,fp); -#else - btAssert(0); -#endif - } - else - { -#ifndef _WIN64 - dataChunk.len = sBulletDNAlen; - dataChunk.oldPtr = sBulletDNAstr; - fwrite(&dataChunk,sizeof(bChunkInd),1,fp); - fwrite(sBulletDNAstr, sBulletDNAlen,1,fp); -#else//_WIN64 - btAssert(0); -#endif//_WIN64 - } -#else//BT_INTERNAL_UPDATE_SERIALIZATION_STRUCTURES - if (VOID_IS_8) - { - dataChunk.len = sBulletDNAlen64; - dataChunk.oldPtr = sBulletDNAstr64; - fwrite(&dataChunk,sizeof(bChunkInd),1,fp); - fwrite(sBulletDNAstr64, sBulletDNAlen64,1,fp); - } - else - { - dataChunk.len = sBulletDNAlen; - dataChunk.oldPtr = sBulletDNAstr; - fwrite(&dataChunk,sizeof(bChunkInd),1,fp); - fwrite(sBulletDNAstr, sBulletDNAlen,1,fp); - } -#endif//BT_INTERNAL_UPDATE_SERIALIZATION_STRUCTURES -} - - -void btBulletFile::parse(int verboseMode) -{ -#ifdef BT_INTERNAL_UPDATE_SERIALIZATION_STRUCTURES - if (VOID_IS_8) - { -#ifdef _WIN64 - - if (m_DnaCopy) - delete m_DnaCopy; - m_DnaCopy = (char*)btAlignedAlloc(sBulletDNAlen64,16); - memcpy(m_DnaCopy,sBulletDNAstr64,sBulletDNAlen64); - parseInternal(verboseMode,(char*)sBulletDNAstr64,sBulletDNAlen64); -#else - btAssert(0); -#endif - } - else - { -#ifndef _WIN64 - - if (m_DnaCopy) - delete m_DnaCopy; - m_DnaCopy = (char*)btAlignedAlloc(sBulletDNAlen,16); - memcpy(m_DnaCopy,sBulletDNAstr,sBulletDNAlen); - parseInternal(verboseMode,m_DnaCopy,sBulletDNAlen); -#else - btAssert(0); -#endif - } -#else//BT_INTERNAL_UPDATE_SERIALIZATION_STRUCTURES - if (VOID_IS_8) - { - if (m_DnaCopy) - delete m_DnaCopy; - m_DnaCopy = (char*)btAlignedAlloc(sBulletDNAlen64,16); - memcpy(m_DnaCopy,sBulletDNAstr64,sBulletDNAlen64); - parseInternal(verboseMode,m_DnaCopy,sBulletDNAlen64); - } - else - { - if (m_DnaCopy) - delete m_DnaCopy; - m_DnaCopy = (char*)btAlignedAlloc(sBulletDNAlen,16); - memcpy(m_DnaCopy,sBulletDNAstr,sBulletDNAlen); - parseInternal(verboseMode,m_DnaCopy,sBulletDNAlen); - } -#endif//BT_INTERNAL_UPDATE_SERIALIZATION_STRUCTURES - - //the parsing will convert to cpu endian - mFlags &=~FD_ENDIAN_SWAP; - - int littleEndian= 1; - littleEndian= ((char*)&littleEndian)[0]; - - mFileBuffer[8] = littleEndian?'v':'V'; - -} - -// experimental -int btBulletFile::write(const char* fileName, bool fixupPointers) -{ - FILE *fp = fopen(fileName, "wb"); - if (fp) - { - char header[SIZEOFBLENDERHEADER] ; - memcpy(header, m_headerString, 7); - int endian= 1; - endian= ((char*)&endian)[0]; - - if (endian) - { - header[7] = '_'; - } else - { - header[7] = '-'; - } - if (VOID_IS_8) - { - header[8]='V'; - } else - { - header[8]='v'; - } - - header[9] = '2'; - header[10] = '7'; - header[11] = '5'; - - fwrite(header,SIZEOFBLENDERHEADER,1,fp); - - writeChunks(fp, fixupPointers); - - writeDNA(fp); - - fclose(fp); - - } else - { - printf("Error: cannot open file %s for writing\n",fileName); - return 0; - } - return 1; -} - - - -void btBulletFile::addStruct(const char* structType,void* data, int len, void* oldPtr, int code) -{ - - bParse::bChunkInd dataChunk; - dataChunk.code = code; - dataChunk.nr = 1; - dataChunk.len = len; - dataChunk.dna_nr = mMemoryDNA->getReverseType(structType); - dataChunk.oldPtr = oldPtr; - - ///Perform structure size validation - short* structInfo= mMemoryDNA->getStruct(dataChunk.dna_nr); - int elemBytes; - elemBytes= mMemoryDNA->getLength(structInfo[0]); -// int elemBytes = mMemoryDNA->getElementSize(structInfo[0],structInfo[1]); - assert(len==elemBytes); - - mLibPointers.insert(dataChunk.oldPtr, (bStructHandle*)data); - m_chunks.push_back(dataChunk); -} - diff --git a/extern/bullet/src/Extras/Serialize/BulletFileLoader/btBulletFile.h b/extern/bullet/src/Extras/Serialize/BulletFileLoader/btBulletFile.h deleted file mode 100644 index b6997c2d581f..000000000000 --- a/extern/bullet/src/Extras/Serialize/BulletFileLoader/btBulletFile.h +++ /dev/null @@ -1,90 +0,0 @@ -/* -bParse -Copyright (c) 2006-2010 Charlie C & Erwin Coumans http://gamekit.googlecode.com - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#ifndef BT_BULLET_FILE_H -#define BT_BULLET_FILE_H - - -#include "bFile.h" -#include "LinearMath/btAlignedObjectArray.h" -#include "bDefines.h" - - -#include "LinearMath/btSerializer.h" - - - -namespace bParse { - - // ----------------------------------------------------- // - class btBulletFile : public bFile - { - - - protected: - - char* m_DnaCopy; - - public: - - btAlignedObjectArray m_multiBodies; - - btAlignedObjectArray m_multiBodyLinkColliders; - - btAlignedObjectArray m_softBodies; - - btAlignedObjectArray m_rigidBodies; - - btAlignedObjectArray m_collisionObjects; - - btAlignedObjectArray m_collisionShapes; - - btAlignedObjectArray m_constraints; - - btAlignedObjectArray m_bvhs; - - btAlignedObjectArray m_triangleInfoMaps; - - btAlignedObjectArray m_dynamicsWorldInfo; - - btAlignedObjectArray m_contactManifolds; - - btAlignedObjectArray m_dataBlocks; - btBulletFile(); - - btBulletFile(const char* fileName); - - btBulletFile(char *memoryBuffer, int len); - - virtual ~btBulletFile(); - - virtual void addDataBlock(char* dataBlock); - - - // experimental - virtual int write(const char* fileName, bool fixupPointers=false); - - virtual void parse(int verboseMode); - - virtual void parseData(); - - virtual void writeDNA(FILE* fp); - - void addStruct(const char* structType,void* data, int len, void* oldPtr, int code); - - }; -}; - -#endif //BT_BULLET_FILE_H diff --git a/extern/bullet/src/Extras/Serialize/BulletFileLoader/premake4.lua b/extern/bullet/src/Extras/Serialize/BulletFileLoader/premake4.lua deleted file mode 100644 index 9fa0cb00c925..000000000000 --- a/extern/bullet/src/Extras/Serialize/BulletFileLoader/premake4.lua +++ /dev/null @@ -1,16 +0,0 @@ - project "BulletFileLoader" - - kind "StaticLib" - - if os.is("Linux") then - buildoptions{"-fPIC"} - end - - includedirs { - "../../../src" - } - - files { - "**.cpp", - "**.h" - } \ No newline at end of file diff --git a/extern/bullet/src/Extras/Serialize/BulletWorldImporter/CMakeLists.txt b/extern/bullet/src/Extras/Serialize/BulletWorldImporter/CMakeLists.txt deleted file mode 100644 index b56b39a89dd4..000000000000 --- a/extern/bullet/src/Extras/Serialize/BulletWorldImporter/CMakeLists.txt +++ /dev/null @@ -1,44 +0,0 @@ -INCLUDE_DIRECTORIES( - ${BULLET_PHYSICS_SOURCE_DIR}/src - ${BULLET_PHYSICS_SOURCE_DIR}/Extras/Serialize/BulletFileLoader -) - -ADD_LIBRARY( -BulletWorldImporter -btMultiBodyWorldImporter.cpp -btBulletWorldImporter.cpp -btBulletWorldImporter.h -btWorldImporter.cpp -btWorldImporter.h -) - -SET_TARGET_PROPERTIES(BulletWorldImporter PROPERTIES VERSION ${BULLET_VERSION}) -SET_TARGET_PROPERTIES(BulletWorldImporter PROPERTIES SOVERSION ${BULLET_VERSION}) - -IF (BUILD_SHARED_LIBS) - TARGET_LINK_LIBRARIES(BulletWorldImporter BulletDynamics BulletCollision BulletFileLoader LinearMath) -ENDIF (BUILD_SHARED_LIBS) - -IF (INSTALL_EXTRA_LIBS) - IF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES) - #FILES_MATCHING requires CMake 2.6 - IF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5) - IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - INSTALL(TARGETS BulletWorldImporter DESTINATION .) - ELSE (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - INSTALL(TARGETS BulletWorldImporter - RUNTIME DESTINATION bin - LIBRARY DESTINATION lib${LIB_SUFFIX} - ARCHIVE DESTINATION lib${LIB_SUFFIX}) - INSTALL(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} -DESTINATION ${INCLUDE_INSTALL_DIR} FILES_MATCHING PATTERN "*.h" PATTERN -".svn" EXCLUDE PATTERN "CMakeFiles" EXCLUDE) - ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - ENDIF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5) - - IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - SET_TARGET_PROPERTIES(BulletWorldImporter PROPERTIES FRAMEWORK true) - SET_TARGET_PROPERTIES(BulletWorldImporter PROPERTIES PUBLIC_HEADER "btBulletWorldImporter.h") - ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - ENDIF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES) -ENDIF (INSTALL_EXTRA_LIBS) diff --git a/extern/bullet/src/Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.cpp b/extern/bullet/src/Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.cpp deleted file mode 100644 index 3605863ec99b..000000000000 --- a/extern/bullet/src/Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.cpp +++ /dev/null @@ -1,361 +0,0 @@ -/* -Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2012 Erwin Coumans http://bulletphysics.org - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - - -#include "btBulletWorldImporter.h" -#include "../BulletFileLoader/btBulletFile.h" - -#include "btBulletDynamicsCommon.h" -#ifndef USE_GIMPACT -#include "BulletCollision/Gimpact/btGImpactShape.h" -#endif - - -//#define USE_INTERNAL_EDGE_UTILITY -#ifdef USE_INTERNAL_EDGE_UTILITY -#include "BulletCollision/CollisionDispatch/btInternalEdgeUtility.h" -#endif //USE_INTERNAL_EDGE_UTILITY - -btBulletWorldImporter::btBulletWorldImporter(btDynamicsWorld* world) - :btWorldImporter(world) -{ -} - -btBulletWorldImporter::~btBulletWorldImporter() -{ -} - - -bool btBulletWorldImporter::loadFile( const char* fileName, const char* preSwapFilenameOut) -{ - bParse::btBulletFile* bulletFile2 = new bParse::btBulletFile(fileName); - - - bool result = loadFileFromMemory(bulletFile2); - //now you could save the file in 'native' format using - //bulletFile2->writeFile("native.bullet"); - if (result) - { - if (preSwapFilenameOut) - { - bulletFile2->preSwap(); - bulletFile2->writeFile(preSwapFilenameOut); - } - - } - delete bulletFile2; - - return result; - -} - - - -bool btBulletWorldImporter::loadFileFromMemory( char* memoryBuffer, int len) -{ - bParse::btBulletFile* bulletFile2 = new bParse::btBulletFile(memoryBuffer,len); - - bool result = loadFileFromMemory(bulletFile2); - - delete bulletFile2; - - return result; -} - - - - -bool btBulletWorldImporter::loadFileFromMemory( bParse::btBulletFile* bulletFile2) -{ - bool ok = (bulletFile2->getFlags()& bParse::FD_OK)!=0; - - if (ok) - bulletFile2->parse(m_verboseMode); - else - return false; - - if (m_verboseMode & bParse::FD_VERBOSE_DUMP_CHUNKS) - { - bulletFile2->dumpChunks(bulletFile2->getFileDNA()); - } - - return convertAllObjects(bulletFile2); - -} - -bool btBulletWorldImporter::convertAllObjects( bParse::btBulletFile* bulletFile2) -{ - - m_shapeMap.clear(); - m_bodyMap.clear(); - - int i; - - for (i=0;im_bvhs.size();i++) - { - btOptimizedBvh* bvh = createOptimizedBvh(); - - if (bulletFile2->getFlags() & bParse::FD_DOUBLE_PRECISION) - { - btQuantizedBvhDoubleData* bvhData = (btQuantizedBvhDoubleData*)bulletFile2->m_bvhs[i]; - bvh->deSerializeDouble(*bvhData); - } else - { - btQuantizedBvhFloatData* bvhData = (btQuantizedBvhFloatData*)bulletFile2->m_bvhs[i]; - bvh->deSerializeFloat(*bvhData); - } - m_bvhMap.insert(bulletFile2->m_bvhs[i],bvh); - } - - - - - - for (i=0;im_collisionShapes.size();i++) - { - btCollisionShapeData* shapeData = (btCollisionShapeData*)bulletFile2->m_collisionShapes[i]; - btCollisionShape* shape = convertCollisionShape(shapeData); - if (shape) - { - // printf("shapeMap.insert(%x,%x)\n",shapeData,shape); - m_shapeMap.insert(shapeData,shape); - } - - if (shape&& shapeData->m_name) - { - char* newname = duplicateName(shapeData->m_name); - m_objectNameMap.insert(shape,newname); - m_nameShapeMap.insert(newname,shape); - } - } - - - - - - for (int i=0;im_dynamicsWorldInfo.size();i++) - { - if (bulletFile2->getFlags() & bParse::FD_DOUBLE_PRECISION) - { - btDynamicsWorldDoubleData* solverInfoData = (btDynamicsWorldDoubleData*)bulletFile2->m_dynamicsWorldInfo[i]; - btContactSolverInfo solverInfo; - - btVector3 gravity; - gravity.deSerializeDouble(solverInfoData->m_gravity); - - solverInfo.m_tau = btScalar(solverInfoData->m_solverInfo.m_tau); - solverInfo.m_damping = btScalar(solverInfoData->m_solverInfo.m_damping); - solverInfo.m_friction = btScalar(solverInfoData->m_solverInfo.m_friction); - solverInfo.m_timeStep = btScalar(solverInfoData->m_solverInfo.m_timeStep); - - solverInfo.m_restitution = btScalar(solverInfoData->m_solverInfo.m_restitution); - solverInfo.m_maxErrorReduction = btScalar(solverInfoData->m_solverInfo.m_maxErrorReduction); - solverInfo.m_sor = btScalar(solverInfoData->m_solverInfo.m_sor); - solverInfo.m_erp = btScalar(solverInfoData->m_solverInfo.m_erp); - - solverInfo.m_erp2 = btScalar(solverInfoData->m_solverInfo.m_erp2); - solverInfo.m_globalCfm = btScalar(solverInfoData->m_solverInfo.m_globalCfm); - solverInfo.m_splitImpulsePenetrationThreshold = btScalar(solverInfoData->m_solverInfo.m_splitImpulsePenetrationThreshold); - solverInfo.m_splitImpulseTurnErp = btScalar(solverInfoData->m_solverInfo.m_splitImpulseTurnErp); - - solverInfo.m_linearSlop = btScalar(solverInfoData->m_solverInfo.m_linearSlop); - solverInfo.m_warmstartingFactor = btScalar(solverInfoData->m_solverInfo.m_warmstartingFactor); - solverInfo.m_maxGyroscopicForce = btScalar(solverInfoData->m_solverInfo.m_maxGyroscopicForce); - solverInfo.m_singleAxisRollingFrictionThreshold = btScalar(solverInfoData->m_solverInfo.m_singleAxisRollingFrictionThreshold); - - solverInfo.m_numIterations = solverInfoData->m_solverInfo.m_numIterations; - solverInfo.m_solverMode = solverInfoData->m_solverInfo.m_solverMode; - solverInfo.m_restingContactRestitutionThreshold = solverInfoData->m_solverInfo.m_restingContactRestitutionThreshold; - solverInfo.m_minimumSolverBatchSize = solverInfoData->m_solverInfo.m_minimumSolverBatchSize; - - solverInfo.m_splitImpulse = solverInfoData->m_solverInfo.m_splitImpulse; - - setDynamicsWorldInfo(gravity,solverInfo); - } else - { - btDynamicsWorldFloatData* solverInfoData = (btDynamicsWorldFloatData*)bulletFile2->m_dynamicsWorldInfo[i]; - btContactSolverInfo solverInfo; - - btVector3 gravity; - gravity.deSerializeFloat(solverInfoData->m_gravity); - - solverInfo.m_tau = solverInfoData->m_solverInfo.m_tau; - solverInfo.m_damping = solverInfoData->m_solverInfo.m_damping; - solverInfo.m_friction = solverInfoData->m_solverInfo.m_friction; - solverInfo.m_timeStep = solverInfoData->m_solverInfo.m_timeStep; - - solverInfo.m_restitution = solverInfoData->m_solverInfo.m_restitution; - solverInfo.m_maxErrorReduction = solverInfoData->m_solverInfo.m_maxErrorReduction; - solverInfo.m_sor = solverInfoData->m_solverInfo.m_sor; - solverInfo.m_erp = solverInfoData->m_solverInfo.m_erp; - - solverInfo.m_erp2 = solverInfoData->m_solverInfo.m_erp2; - solverInfo.m_globalCfm = solverInfoData->m_solverInfo.m_globalCfm; - solverInfo.m_splitImpulsePenetrationThreshold = solverInfoData->m_solverInfo.m_splitImpulsePenetrationThreshold; - solverInfo.m_splitImpulseTurnErp = solverInfoData->m_solverInfo.m_splitImpulseTurnErp; - - solverInfo.m_linearSlop = solverInfoData->m_solverInfo.m_linearSlop; - solverInfo.m_warmstartingFactor = solverInfoData->m_solverInfo.m_warmstartingFactor; - solverInfo.m_maxGyroscopicForce = solverInfoData->m_solverInfo.m_maxGyroscopicForce; - solverInfo.m_singleAxisRollingFrictionThreshold = solverInfoData->m_solverInfo.m_singleAxisRollingFrictionThreshold; - - solverInfo.m_numIterations = solverInfoData->m_solverInfo.m_numIterations; - solverInfo.m_solverMode = solverInfoData->m_solverInfo.m_solverMode; - solverInfo.m_restingContactRestitutionThreshold = solverInfoData->m_solverInfo.m_restingContactRestitutionThreshold; - solverInfo.m_minimumSolverBatchSize = solverInfoData->m_solverInfo.m_minimumSolverBatchSize; - - solverInfo.m_splitImpulse = solverInfoData->m_solverInfo.m_splitImpulse; - - setDynamicsWorldInfo(gravity,solverInfo); - } - } - - - for (i=0;im_rigidBodies.size();i++) - { - if (bulletFile2->getFlags() & bParse::FD_DOUBLE_PRECISION) - { - btRigidBodyDoubleData* colObjData = (btRigidBodyDoubleData*)bulletFile2->m_rigidBodies[i]; - convertRigidBodyDouble(colObjData); - } else - { - btRigidBodyFloatData* colObjData = (btRigidBodyFloatData*)bulletFile2->m_rigidBodies[i]; - convertRigidBodyFloat(colObjData); - } - - - } - - for (i=0;im_collisionObjects.size();i++) - { - if (bulletFile2->getFlags() & bParse::FD_DOUBLE_PRECISION) - { - btCollisionObjectDoubleData* colObjData = (btCollisionObjectDoubleData*)bulletFile2->m_collisionObjects[i]; - btCollisionShape** shapePtr = m_shapeMap.find(colObjData->m_collisionShape); - if (shapePtr && *shapePtr) - { - btTransform startTransform; - colObjData->m_worldTransform.m_origin.m_floats[3] = 0.f; - startTransform.deSerializeDouble(colObjData->m_worldTransform); - - btCollisionShape* shape = (btCollisionShape*)*shapePtr; - btCollisionObject* body = createCollisionObject(startTransform,shape,colObjData->m_name); - body->setFriction(btScalar(colObjData->m_friction)); - body->setRestitution(btScalar(colObjData->m_restitution)); - -#ifdef USE_INTERNAL_EDGE_UTILITY - if (shape->getShapeType() == TRIANGLE_MESH_SHAPE_PROXYTYPE) - { - btBvhTriangleMeshShape* trimesh = (btBvhTriangleMeshShape*)shape; - if (trimesh->getTriangleInfoMap()) - { - body->setCollisionFlags(body->getCollisionFlags() | btCollisionObject::CF_CUSTOM_MATERIAL_CALLBACK); - } - } -#endif //USE_INTERNAL_EDGE_UTILITY - m_bodyMap.insert(colObjData,body); - } else - { - printf("error: no shape found\n"); - } - - } else - { - btCollisionObjectFloatData* colObjData = (btCollisionObjectFloatData*)bulletFile2->m_collisionObjects[i]; - btCollisionShape** shapePtr = m_shapeMap.find(colObjData->m_collisionShape); - if (shapePtr && *shapePtr) - { - btTransform startTransform; - colObjData->m_worldTransform.m_origin.m_floats[3] = 0.f; - startTransform.deSerializeFloat(colObjData->m_worldTransform); - - btCollisionShape* shape = (btCollisionShape*)*shapePtr; - btCollisionObject* body = createCollisionObject(startTransform,shape,colObjData->m_name); - -#ifdef USE_INTERNAL_EDGE_UTILITY - if (shape->getShapeType() == TRIANGLE_MESH_SHAPE_PROXYTYPE) - { - btBvhTriangleMeshShape* trimesh = (btBvhTriangleMeshShape*)shape; - if (trimesh->getTriangleInfoMap()) - { - body->setCollisionFlags(body->getCollisionFlags() | btCollisionObject::CF_CUSTOM_MATERIAL_CALLBACK); - } - } -#endif //USE_INTERNAL_EDGE_UTILITY - m_bodyMap.insert(colObjData,body); - } else - { - printf("error: no shape found\n"); - } - } - - } - - - for (i=0;im_constraints.size();i++) - { - btTypedConstraintData2* constraintData = (btTypedConstraintData2*)bulletFile2->m_constraints[i]; - - btCollisionObject** colAptr = m_bodyMap.find(constraintData->m_rbA); - btCollisionObject** colBptr = m_bodyMap.find(constraintData->m_rbB); - - btRigidBody* rbA = 0; - btRigidBody* rbB = 0; - - if (colAptr) - { - rbA = btRigidBody::upcast(*colAptr); - if (!rbA) - rbA = &getFixedBody(); - } - if (colBptr) - { - rbB = btRigidBody::upcast(*colBptr); - if (!rbB) - rbB = &getFixedBody(); - } - if (!rbA && !rbB) - continue; - - bool isDoublePrecisionData = (bulletFile2->getFlags() & bParse::FD_DOUBLE_PRECISION)!=0; - - if (isDoublePrecisionData) - { - if (bulletFile2->getVersion()>=282) - { - btTypedConstraintDoubleData* dc = (btTypedConstraintDoubleData*)constraintData; - convertConstraintDouble(dc, rbA,rbB, bulletFile2->getVersion()); - } else - { - //double-precision constraints were messed up until 2.82, try to recover data... - - btTypedConstraintData* oldData = (btTypedConstraintData*)constraintData; - - convertConstraintBackwardsCompatible281(oldData, rbA,rbB, bulletFile2->getVersion()); - - } - } - else - { - btTypedConstraintFloatData* dc = (btTypedConstraintFloatData*)constraintData; - convertConstraintFloat(dc, rbA,rbB, bulletFile2->getVersion()); - } - - - } - - return true; -} - diff --git a/extern/bullet/src/Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.h b/extern/bullet/src/Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.h deleted file mode 100644 index 27c1e7e33210..000000000000 --- a/extern/bullet/src/Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.h +++ /dev/null @@ -1,68 +0,0 @@ -/* -Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2012 Erwin Coumans http://bulletphysics.org - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - - -#ifndef BULLET_WORLD_IMPORTER_H -#define BULLET_WORLD_IMPORTER_H - - -#include "btWorldImporter.h" - - -class btBulletFile; - - - - -namespace bParse -{ - class btBulletFile; - -}; - - - -///The btBulletWorldImporter is a starting point to import .bullet files. -///note that not all data is converted yet. You are expected to override or modify this class. -///See Bullet/Demos/SerializeDemo for a derived class that extract btSoftBody objects too. -class btBulletWorldImporter : public btWorldImporter -{ - - -public: - - btBulletWorldImporter(btDynamicsWorld* world=0); - - virtual ~btBulletWorldImporter(); - - ///if you pass a valid preSwapFilenameOut, it will save a new file with a different endianness - ///this pre-swapped file can be loaded without swapping on a target platform of different endianness - bool loadFile(const char* fileName, const char* preSwapFilenameOut=0); - - ///the memoryBuffer might be modified (for example if endian swaps are necessary) - bool loadFileFromMemory(char *memoryBuffer, int len); - - bool loadFileFromMemory(bParse::btBulletFile* file); - - //call make sure bulletFile2 has been parsed, either using btBulletFile::parse or btBulletWorldImporter::loadFileFromMemory - virtual bool convertAllObjects(bParse::btBulletFile* file); - - - - -}; - -#endif //BULLET_WORLD_IMPORTER_H - diff --git a/extern/bullet/src/Extras/Serialize/BulletWorldImporter/btMultiBodyWorldImporter.cpp b/extern/bullet/src/Extras/Serialize/BulletWorldImporter/btMultiBodyWorldImporter.cpp deleted file mode 100644 index f7eb15c75cdb..000000000000 --- a/extern/bullet/src/Extras/Serialize/BulletWorldImporter/btMultiBodyWorldImporter.cpp +++ /dev/null @@ -1,523 +0,0 @@ -#include "btMultiBodyWorldImporter.h" - -#include "LinearMath/btSerializer.h" -#include "../BulletFileLoader/btBulletFile.h" -#include "btBulletWorldImporter.h" -#include "btBulletDynamicsCommon.h" -#include "BulletDynamics/Featherstone/btMultiBody.h" -#include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h" -#include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h" - -struct btMultiBodyWorldImporterInternalData -{ - btMultiBodyDynamicsWorld* m_mbDynamicsWorld; - btHashMap m_mbMap; -}; - -btMultiBodyWorldImporter::btMultiBodyWorldImporter(btMultiBodyDynamicsWorld* world) - :btBulletWorldImporter(world) -{ - m_data = new btMultiBodyWorldImporterInternalData; - m_data->m_mbDynamicsWorld = world; -} - - -btMultiBodyWorldImporter::~btMultiBodyWorldImporter() -{ - delete m_data; -} - -void btMultiBodyWorldImporter::deleteAllData() -{ - btBulletWorldImporter::deleteAllData(); -} - - -static btCollisionObjectDoubleData* getBody0FromContactManifold(btPersistentManifoldDoubleData* manifold) -{ - return (btCollisionObjectDoubleData*)manifold->m_body0; -} -static btCollisionObjectDoubleData* getBody1FromContactManifold(btPersistentManifoldDoubleData* manifold) -{ - return (btCollisionObjectDoubleData*)manifold->m_body1; -} -static btCollisionObjectFloatData* getBody0FromContactManifold(btPersistentManifoldFloatData* manifold) -{ - return (btCollisionObjectFloatData*)manifold->m_body0; -} -static btCollisionObjectFloatData* getBody1FromContactManifold(btPersistentManifoldFloatData* manifold) -{ - return (btCollisionObjectFloatData*)manifold->m_body1; -} - - -template void syncContactManifolds(T** contactManifolds, int numContactManifolds, btMultiBodyWorldImporterInternalData* m_data) -{ - m_data->m_mbDynamicsWorld->updateAabbs(); - m_data->m_mbDynamicsWorld->computeOverlappingPairs(); - btDispatcher* dispatcher = m_data->m_mbDynamicsWorld->getDispatcher(); - - btDispatcherInfo& dispatchInfo = m_data->m_mbDynamicsWorld->getDispatchInfo(); - - - if (dispatcher) - { - btOverlappingPairCache* pairCache = m_data->m_mbDynamicsWorld->getBroadphase()->getOverlappingPairCache(); - if (dispatcher) - { - dispatcher->dispatchAllCollisionPairs(pairCache, dispatchInfo, dispatcher); - } - int numExistingManifolds = m_data->m_mbDynamicsWorld->getDispatcher()->getNumManifolds(); - btManifoldArray manifoldArray; - for (int i = 0; i < pairCache->getNumOverlappingPairs(); i++) - { - btBroadphasePair& pair = pairCache->getOverlappingPairArray()[i]; - if (pair.m_algorithm) - { - pair.m_algorithm->getAllContactManifolds(manifoldArray); - //for each existing manifold, search a matching manifoldData and reconstruct - for (int m = 0; m < manifoldArray.size(); m++) - { - btPersistentManifold* existingManifold = manifoldArray[m]; - int uid0 = existingManifold->getBody0()->getBroadphaseHandle()->m_uniqueId; - int uid1 = existingManifold->getBody1()->getBroadphaseHandle()->m_uniqueId; - int matchingManifoldIndex = -1; - for (int q = 0; q < numContactManifolds; q++) - { - if (uid0 == getBody0FromContactManifold(contactManifolds[q])->m_uniqueId && uid1 == getBody1FromContactManifold(contactManifolds[q])->m_uniqueId) - { - matchingManifoldIndex = q; - } - } - if (matchingManifoldIndex >= 0) - { - existingManifold->deSerialize(contactManifolds[matchingManifoldIndex]); - } - else - { - existingManifold->setNumContacts(0); - //printf("Issue: cannot find maching contact manifold (%d, %d), may cause issues in determinism.\n", uid0, uid1); - } - - manifoldArray.clear(); - } - } - } - } - -} - -template void syncMultiBody(T* mbd, btMultiBody* mb, btMultiBodyWorldImporterInternalData* m_data, btAlignedObjectArray& scratchQ, btAlignedObjectArray& scratchM) -{ - bool isFixedBase = mbd->m_baseMass == 0; - bool canSleep = false; - btVector3 baseInertia; - baseInertia.deSerialize(mbd->m_baseInertia); - - btVector3 baseWorldPos; - baseWorldPos.deSerialize(mbd->m_baseWorldPosition); - mb->setBasePos(baseWorldPos); - btQuaternion baseWorldRot; - baseWorldRot.deSerialize(mbd->m_baseWorldOrientation); - mb->setWorldToBaseRot(baseWorldRot.inverse()); - btVector3 baseLinVal; - baseLinVal.deSerialize(mbd->m_baseLinearVelocity); - btVector3 baseAngVel; - baseAngVel.deSerialize(mbd->m_baseAngularVelocity); - mb->setBaseVel(baseLinVal); - mb->setBaseOmega(baseAngVel); - - for (int i = 0; i < mbd->m_numLinks; i++) - { - - mb->getLink(i).m_absFrameTotVelocity.m_topVec.deSerialize(mbd->m_links[i].m_absFrameTotVelocityTop); - mb->getLink(i).m_absFrameTotVelocity.m_bottomVec.deSerialize(mbd->m_links[i].m_absFrameTotVelocityBottom); - mb->getLink(i).m_absFrameLocVelocity.m_topVec.deSerialize(mbd->m_links[i].m_absFrameLocVelocityTop); - mb->getLink(i).m_absFrameLocVelocity.m_bottomVec.deSerialize(mbd->m_links[i].m_absFrameLocVelocityBottom); - - switch (mbd->m_links[i].m_jointType) - { - case btMultibodyLink::eFixed: - { - break; - } - case btMultibodyLink::ePrismatic: - { - mb->setJointPos(i, mbd->m_links[i].m_jointPos[0]); - mb->setJointVel(i, mbd->m_links[i].m_jointVel[0]); - break; - } - case btMultibodyLink::eRevolute: - { - mb->setJointPos(i, mbd->m_links[i].m_jointPos[0]); - mb->setJointVel(i, mbd->m_links[i].m_jointVel[0]); - break; - } - case btMultibodyLink::eSpherical: - { - btScalar jointPos[4] = { (btScalar)mbd->m_links[i].m_jointPos[0], (btScalar)mbd->m_links[i].m_jointPos[1], (btScalar)mbd->m_links[i].m_jointPos[2], (btScalar)mbd->m_links[i].m_jointPos[3] }; - btScalar jointVel[3] = { (btScalar)mbd->m_links[i].m_jointVel[0], (btScalar)mbd->m_links[i].m_jointVel[1], (btScalar)mbd->m_links[i].m_jointVel[2] }; - mb->setJointPosMultiDof(i, jointPos); - mb->setJointVelMultiDof(i, jointVel); - - break; - } - case btMultibodyLink::ePlanar: - { - break; - } - default: - { - } - } - } - mb->forwardKinematics(scratchQ, scratchM); - mb->updateCollisionObjectWorldTransforms(scratchQ, scratchM); -} - -template void convertMultiBody(T* mbd, btMultiBodyWorldImporterInternalData* m_data) -{ - bool isFixedBase = mbd->m_baseMass == 0; - bool canSleep = false; - btVector3 baseInertia; - baseInertia.deSerialize(mbd->m_baseInertia); - btMultiBody* mb = new btMultiBody(mbd->m_numLinks, mbd->m_baseMass, baseInertia, isFixedBase, canSleep); - mb->setHasSelfCollision(false); - - btVector3 baseWorldPos; - baseWorldPos.deSerialize(mbd->m_baseWorldPosition); - - btQuaternion baseWorldOrn; - baseWorldOrn.deSerialize(mbd->m_baseWorldOrientation); - mb->setBasePos(baseWorldPos); - mb->setWorldToBaseRot(baseWorldOrn.inverse()); - - m_data->m_mbMap.insert(mbd, mb); - for (int i = 0; i < mbd->m_numLinks; i++) - { - btVector3 localInertiaDiagonal; - localInertiaDiagonal.deSerialize(mbd->m_links[i].m_linkInertia); - btQuaternion parentRotToThis; - parentRotToThis.deSerialize(mbd->m_links[i].m_zeroRotParentToThis); - btVector3 parentComToThisPivotOffset; - parentComToThisPivotOffset.deSerialize(mbd->m_links[i].m_parentComToThisPivotOffset); - btVector3 thisPivotToThisComOffset; - thisPivotToThisComOffset.deSerialize(mbd->m_links[i].m_thisPivotToThisComOffset); - - switch (mbd->m_links[i].m_jointType) - { - case btMultibodyLink::eFixed: - { - - - mb->setupFixed(i, mbd->m_links[i].m_linkMass, localInertiaDiagonal, mbd->m_links[i].m_parentIndex, - parentRotToThis, parentComToThisPivotOffset, thisPivotToThisComOffset); - //search for the collider - //mbd->m_links[i].m_linkCollider - break; - } - case btMultibodyLink::ePrismatic: - { - btVector3 jointAxis; - jointAxis.deSerialize(mbd->m_links[i].m_jointAxisBottom[0]); - bool disableParentCollision = true;//todo - mb->setupPrismatic(i, mbd->m_links[i].m_linkMass, localInertiaDiagonal, mbd->m_links[i].m_parentIndex, - parentRotToThis, jointAxis, parentComToThisPivotOffset, thisPivotToThisComOffset, disableParentCollision); - mb->setJointPos(i, mbd->m_links[i].m_jointPos[0]); - mb->setJointVel(i, mbd->m_links[i].m_jointVel[0]); - break; - } - case btMultibodyLink::eRevolute: - { - btVector3 jointAxis; - jointAxis.deSerialize(mbd->m_links[i].m_jointAxisTop[0]); - bool disableParentCollision = true;//todo - mb->setupRevolute(i, mbd->m_links[i].m_linkMass, localInertiaDiagonal, mbd->m_links[i].m_parentIndex, - parentRotToThis, jointAxis, parentComToThisPivotOffset, thisPivotToThisComOffset, disableParentCollision); - mb->setJointPos(i, mbd->m_links[i].m_jointPos[0]); - mb->setJointVel(i, mbd->m_links[i].m_jointVel[0]); - break; - } - case btMultibodyLink::eSpherical: - { - btAssert(0); - bool disableParentCollision = true;//todo - mb->setupSpherical(i, mbd->m_links[i].m_linkMass, localInertiaDiagonal, mbd->m_links[i].m_parentIndex, - parentRotToThis, parentComToThisPivotOffset, thisPivotToThisComOffset, disableParentCollision); - btScalar jointPos[4] = { (btScalar)mbd->m_links[i].m_jointPos[0], (btScalar)mbd->m_links[i].m_jointPos[1], (btScalar)mbd->m_links[i].m_jointPos[2], (btScalar)mbd->m_links[i].m_jointPos[3] }; - btScalar jointVel[3] = { (btScalar)mbd->m_links[i].m_jointVel[0], (btScalar)mbd->m_links[i].m_jointVel[1], (btScalar)mbd->m_links[i].m_jointVel[2] }; - mb->setJointPosMultiDof(i, jointPos); - mb->setJointVelMultiDof(i, jointVel); - - break; - } - case btMultibodyLink::ePlanar: - { - btAssert(0); - break; - } - default: - { - btAssert(0); - } - } - } -} - -bool btMultiBodyWorldImporter::convertAllObjects( bParse::btBulletFile* bulletFile2) -{ - bool result = false; - btAlignedObjectArray scratchQ; - btAlignedObjectArray scratchM; - - if (m_importerFlags&eRESTORE_EXISTING_OBJECTS) - { - //check if the snapshot is valid for the existing world - //equal number of objects, # links etc - if ((bulletFile2->m_multiBodies.size() != m_data->m_mbDynamicsWorld->getNumMultibodies())) - { - result = false; - return result; - } - result = true; - - //convert all multibodies - if (bulletFile2->getFlags() & bParse::FD_DOUBLE_PRECISION) - { - - //for (int i = 0; i < bulletFile2->m_multiBodies.size(); i++) - for (int i = bulletFile2->m_multiBodies.size() - 1; i >= 0; i--) - { - btMultiBodyDoubleData* mbd = (btMultiBodyDoubleData*)bulletFile2->m_multiBodies[i]; - btMultiBody* mb = m_data->m_mbDynamicsWorld->getMultiBody(i); - syncMultiBody(mbd, mb, m_data, scratchQ, scratchM); - } - - for (int i = bulletFile2->m_rigidBodies.size() - 1; i >= 0; i--) - { - btRigidBodyDoubleData* rbd = (btRigidBodyDoubleData*)bulletFile2->m_rigidBodies[i]; - int foundRb = -1; - int uid = rbd->m_collisionObjectData.m_uniqueId; - for (int i = 0; i < m_data->m_mbDynamicsWorld->getNumCollisionObjects(); i++) - { - if (uid == m_data->m_mbDynamicsWorld->getCollisionObjectArray()[i]->getBroadphaseHandle()->m_uniqueId) - { - foundRb = i; - break; - } - } - if (foundRb >= 0) - { - btRigidBody* rb = btRigidBody::upcast(m_data->m_mbDynamicsWorld->getCollisionObjectArray()[foundRb]); - if (rb) - { - btTransform tr; - tr.deSerializeDouble(rbd->m_collisionObjectData.m_worldTransform); - rb->setWorldTransform(tr); - btVector3 linVel, angVel; - linVel.deSerializeDouble(rbd->m_linearVelocity); - angVel.deSerializeDouble(rbd->m_angularVelocity); - rb->setLinearVelocity(linVel); - rb->setAngularVelocity(angVel); - } - else - { - result = false; - } - } - else - { - result = false; - } - } - - //todo: check why body1 pointer is not properly deserialized - for (int i = 0; i < bulletFile2->m_contactManifolds.size(); i++) - { - btPersistentManifoldDoubleData* manifoldData = (btPersistentManifoldDoubleData*)bulletFile2->m_contactManifolds[i]; - { - void* ptr = bulletFile2->findLibPointer(manifoldData->m_body0); - if (ptr) - { - manifoldData->m_body0 = (btCollisionObjectDoubleData*)ptr; - } - } - - { - void* ptr = bulletFile2->findLibPointer(manifoldData->m_body1); - if (ptr) - { - manifoldData->m_body1 = (btCollisionObjectDoubleData*)ptr; - } - } - } - - - if (bulletFile2->m_contactManifolds.size()) - { - syncContactManifolds((btPersistentManifoldDoubleData**)&bulletFile2->m_contactManifolds[0], bulletFile2->m_contactManifolds.size(), m_data); - } - } - else - { - //single precision version - //for (int i = 0; i < bulletFile2->m_multiBodies.size(); i++) - for (int i = bulletFile2->m_multiBodies.size() - 1; i >= 0; i--) - { - btMultiBodyFloatData* mbd = (btMultiBodyFloatData*)bulletFile2->m_multiBodies[i]; - btMultiBody* mb = m_data->m_mbDynamicsWorld->getMultiBody(i); - syncMultiBody(mbd, mb, m_data, scratchQ, scratchM); - } - - //todo: check why body1 pointer is not properly deserialized - for (int i = 0; i < bulletFile2->m_contactManifolds.size(); i++) - { - btPersistentManifoldFloatData* manifoldData = (btPersistentManifoldFloatData*)bulletFile2->m_contactManifolds[i]; - { - void* ptr = bulletFile2->findLibPointer(manifoldData->m_body0); - if (ptr) - { - manifoldData->m_body0 = (btCollisionObjectFloatData*)ptr; - } - } - { - void* ptr = bulletFile2->findLibPointer(manifoldData->m_body1); - if (ptr) - { - manifoldData->m_body1 = (btCollisionObjectFloatData*)ptr; - } - } - } - - - if (bulletFile2->m_contactManifolds.size()) - { - syncContactManifolds((btPersistentManifoldFloatData**)&bulletFile2->m_contactManifolds[0], bulletFile2->m_contactManifolds.size(), m_data); - } - - } - } - else - { - result = btBulletWorldImporter::convertAllObjects(bulletFile2); - - - //convert all multibodies - for (int i = 0; i < bulletFile2->m_multiBodies.size(); i++) - { - - if (bulletFile2->getFlags() & bParse::FD_DOUBLE_PRECISION) - { - btMultiBodyDoubleData* mbd = (btMultiBodyDoubleData*)bulletFile2->m_multiBodies[i]; - convertMultiBody(mbd, m_data); - } - else - { - btMultiBodyFloatData* mbd = (btMultiBodyFloatData*)bulletFile2->m_multiBodies[i]; - convertMultiBody(mbd, m_data); - } - } - - //forward kinematics, so that the link world transforms are valid, for collision detection - for (int i = 0; i < m_data->m_mbMap.size(); i++) - { - btMultiBody**ptr = m_data->m_mbMap.getAtIndex(i); - if (ptr) - { - btMultiBody* mb = *ptr; - mb->finalizeMultiDof(); - btVector3 linvel = mb->getBaseVel(); - btVector3 angvel = mb->getBaseOmega(); - mb->forwardKinematics(scratchQ, scratchM); - } - } - - //convert all multibody link colliders - for (int i = 0; i < bulletFile2->m_multiBodyLinkColliders.size(); i++) - { - if (bulletFile2->getFlags() & bParse::FD_DOUBLE_PRECISION) - { - btMultiBodyLinkColliderDoubleData* mblcd = (btMultiBodyLinkColliderDoubleData*)bulletFile2->m_multiBodyLinkColliders[i]; - - btMultiBody** ptr = m_data->m_mbMap[mblcd->m_multiBody]; - if (ptr) - { - btMultiBody* multiBody = *ptr; - - - btCollisionShape** shapePtr = m_shapeMap.find(mblcd->m_colObjData.m_collisionShape); - if (shapePtr && *shapePtr) - { - btTransform startTransform; - mblcd->m_colObjData.m_worldTransform.m_origin.m_floats[3] = 0.f; - startTransform.deSerializeDouble(mblcd->m_colObjData.m_worldTransform); - - btCollisionShape* shape = (btCollisionShape*)*shapePtr; - if (shape) - { - btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(multiBody, mblcd->m_link); - col->setCollisionShape(shape); - //btCollisionObject* body = createCollisionObject(startTransform,shape,mblcd->m_colObjData.m_name); - col->setFriction(btScalar(mblcd->m_colObjData.m_friction)); - col->setRestitution(btScalar(mblcd->m_colObjData.m_restitution)); - //m_bodyMap.insert(colObjData,body); - if (mblcd->m_link == -1) - { - col->setWorldTransform(multiBody->getBaseWorldTransform()); - multiBody->setBaseCollider(col); - } - else - { - col->setWorldTransform(multiBody->getLink(mblcd->m_link).m_cachedWorldTransform); - multiBody->getLink(mblcd->m_link).m_collider = col; - } - int mbLinkIndex = mblcd->m_link; - - bool isDynamic = (mbLinkIndex < 0 && multiBody->hasFixedBase()) ? false : true; - int collisionFilterGroup = isDynamic ? int(btBroadphaseProxy::DefaultFilter) : int(btBroadphaseProxy::StaticFilter); - int collisionFilterMask = isDynamic ? int(btBroadphaseProxy::AllFilter) : int(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter); - -#if 0 - int colGroup = 0, colMask = 0; - int collisionFlags = mblcd->m_colObjData.m_collisionFlags; - if (collisionFlags & URDF_HAS_COLLISION_GROUP) - { - collisionFilterGroup = colGroup; - } - if (collisionFlags & URDF_HAS_COLLISION_MASK) - { - collisionFilterMask = colMask; - } -#endif - m_data->m_mbDynamicsWorld->addCollisionObject(col, collisionFilterGroup, collisionFilterMask); - } - - } - else - { - printf("error: no shape found\n"); - } -#if 0 - //base and fixed? -> static, otherwise flag as dynamic - - world1->addCollisionObject(col, collisionFilterGroup, collisionFilterMask); -#endif - } - - } - } - - for (int i = 0; i < m_data->m_mbMap.size(); i++) - { - btMultiBody**ptr = m_data->m_mbMap.getAtIndex(i); - if (ptr) - { - btMultiBody* mb = *ptr; - mb->finalizeMultiDof(); - - m_data->m_mbDynamicsWorld->addMultiBody(mb); - } - } - } - return result; -} \ No newline at end of file diff --git a/extern/bullet/src/Extras/Serialize/BulletWorldImporter/btMultiBodyWorldImporter.h b/extern/bullet/src/Extras/Serialize/BulletWorldImporter/btMultiBodyWorldImporter.h deleted file mode 100644 index 002616e40a5a..000000000000 --- a/extern/bullet/src/Extras/Serialize/BulletWorldImporter/btMultiBodyWorldImporter.h +++ /dev/null @@ -1,20 +0,0 @@ -#ifndef BT_MULTIBODY_WORLD_IMPORTER_H -#define BT_MULTIBODY_WORLD_IMPORTER_H - -#include "btBulletWorldImporter.h" - -class btMultiBodyWorldImporter : public btBulletWorldImporter -{ - struct btMultiBodyWorldImporterInternalData* m_data; - -public: - - btMultiBodyWorldImporter(class btMultiBodyDynamicsWorld* world); - virtual ~btMultiBodyWorldImporter(); - - virtual bool convertAllObjects( bParse::btBulletFile* bulletFile2); - - virtual void deleteAllData(); -}; - -#endif //BT_MULTIBODY_WORLD_IMPORTER_H diff --git a/extern/bullet/src/Extras/Serialize/BulletWorldImporter/btWorldImporter.cpp b/extern/bullet/src/Extras/Serialize/BulletWorldImporter/btWorldImporter.cpp deleted file mode 100644 index 080b19aefae0..000000000000 --- a/extern/bullet/src/Extras/Serialize/BulletWorldImporter/btWorldImporter.cpp +++ /dev/null @@ -1,2123 +0,0 @@ -/* -Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2012 Erwin Coumans http://bulletphysics.org - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#include "btWorldImporter.h" -#include "btBulletDynamicsCommon.h" -#ifdef USE_GIMPACT -#include "BulletCollision/Gimpact/btGImpactShape.h" -#endif -btWorldImporter::btWorldImporter(btDynamicsWorld* world) -:m_dynamicsWorld(world), -m_verboseMode(0), -m_importerFlags(0) -{ - -} - -btWorldImporter::~btWorldImporter() -{ -} - -void btWorldImporter::deleteAllData() -{ - int i; - for (i=0;iremoveConstraint(m_allocatedConstraints[i]); - delete m_allocatedConstraints[i]; - } - m_allocatedConstraints.clear(); - - - for (i=0;iremoveRigidBody(btRigidBody::upcast(m_allocatedRigidBodies[i])); - delete m_allocatedRigidBodies[i]; - } - - m_allocatedRigidBodies.clear(); - - - for (i=0;im_numMeshParts;a++) - { - btMeshPartData* curPart = &curData->m_meshPartsPtr[a]; - if(curPart->m_vertices3f) - delete [] curPart->m_vertices3f; - - if(curPart->m_vertices3d) - delete [] curPart->m_vertices3d; - - if(curPart->m_indices32) - delete [] curPart->m_indices32; - - if(curPart->m_3indices16) - delete [] curPart->m_3indices16; - - if(curPart->m_indices16) - delete [] curPart->m_indices16; - - if (curPart->m_3indices8) - delete [] curPart->m_3indices8; - - } - delete [] curData->m_meshPartsPtr; - delete curData; - } - m_allocatedbtStridingMeshInterfaceDatas.clear(); - - for (i=0;im_shapeType) - { - case STATIC_PLANE_PROXYTYPE: - { - btStaticPlaneShapeData* planeData = (btStaticPlaneShapeData*)shapeData; - btVector3 planeNormal,localScaling; - planeNormal.deSerializeFloat(planeData->m_planeNormal); - localScaling.deSerializeFloat(planeData->m_localScaling); - shape = createPlaneShape(planeNormal,planeData->m_planeConstant); - shape->setLocalScaling(localScaling); - - break; - } - case SCALED_TRIANGLE_MESH_SHAPE_PROXYTYPE: - { - btScaledTriangleMeshShapeData* scaledMesh = (btScaledTriangleMeshShapeData*) shapeData; - btCollisionShapeData* colShapeData = (btCollisionShapeData*) &scaledMesh->m_trimeshShapeData; - colShapeData->m_shapeType = TRIANGLE_MESH_SHAPE_PROXYTYPE; - btCollisionShape* childShape = convertCollisionShape(colShapeData); - btBvhTriangleMeshShape* meshShape = (btBvhTriangleMeshShape*)childShape; - btVector3 localScaling; - localScaling.deSerializeFloat(scaledMesh->m_localScaling); - - shape = createScaledTrangleMeshShape(meshShape, localScaling); - break; - } - case GIMPACT_SHAPE_PROXYTYPE: - { -#ifdef USE_GIMPACT - btGImpactMeshShapeData* gimpactData = (btGImpactMeshShapeData*) shapeData; - if (gimpactData->m_gimpactSubType == CONST_GIMPACT_TRIMESH_SHAPE) - { - btStridingMeshInterfaceData* interfaceData = createStridingMeshInterfaceData(&gimpactData->m_meshInterface); - btTriangleIndexVertexArray* meshInterface = createMeshInterface(*interfaceData); - - - btGImpactMeshShape* gimpactShape = createGimpactShape(meshInterface); - btVector3 localScaling; - localScaling.deSerializeFloat(gimpactData->m_localScaling); - gimpactShape->setLocalScaling(localScaling); - gimpactShape->setMargin(btScalar(gimpactData->m_collisionMargin)); - gimpactShape->updateBound(); - shape = gimpactShape; - } else - { - printf("unsupported gimpact sub type\n"); - } -#endif//USE_GIMPACT - break; - } - //The btCapsuleShape* API has issue passing the margin/scaling/halfextents unmodified through the API - //so deal with this - case CAPSULE_SHAPE_PROXYTYPE: - { - btCapsuleShapeData* capData = (btCapsuleShapeData*)shapeData; - - - switch (capData->m_upAxis) - { - case 0: - { - shape = createCapsuleShapeX(1,1); - break; - } - case 1: - { - shape = createCapsuleShapeY(1,1); - break; - } - case 2: - { - shape = createCapsuleShapeZ(1,1); - break; - } - default: - { - printf("error: wrong up axis for btCapsuleShape\n"); - } - - - }; - if (shape) - { - btCapsuleShape* cap = (btCapsuleShape*) shape; - cap->deSerializeFloat(capData); - } - break; - } - case CYLINDER_SHAPE_PROXYTYPE: - case CONE_SHAPE_PROXYTYPE: - case BOX_SHAPE_PROXYTYPE: - case SPHERE_SHAPE_PROXYTYPE: - case MULTI_SPHERE_SHAPE_PROXYTYPE: - case CONVEX_HULL_SHAPE_PROXYTYPE: - { - btConvexInternalShapeData* bsd = (btConvexInternalShapeData*)shapeData; - btVector3 implicitShapeDimensions; - implicitShapeDimensions.deSerializeFloat(bsd->m_implicitShapeDimensions); - btVector3 localScaling; - localScaling.deSerializeFloat(bsd->m_localScaling); - btVector3 margin(bsd->m_collisionMargin,bsd->m_collisionMargin,bsd->m_collisionMargin); - switch (shapeData->m_shapeType) - { - case BOX_SHAPE_PROXYTYPE: - { - btBoxShape* box= (btBoxShape*)createBoxShape(implicitShapeDimensions/localScaling+margin); - //box->initializePolyhedralFeatures(); - shape = box; - - break; - } - case SPHERE_SHAPE_PROXYTYPE: - { - shape = createSphereShape(implicitShapeDimensions.getX()); - break; - } - - case CYLINDER_SHAPE_PROXYTYPE: - { - btCylinderShapeData* cylData = (btCylinderShapeData*) shapeData; - btVector3 halfExtents = implicitShapeDimensions+margin; - switch (cylData->m_upAxis) - { - case 0: - { - shape = createCylinderShapeX(halfExtents.getY(),halfExtents.getX()); - break; - } - case 1: - { - shape = createCylinderShapeY(halfExtents.getX(),halfExtents.getY()); - break; - } - case 2: - { - shape = createCylinderShapeZ(halfExtents.getX(),halfExtents.getZ()); - break; - } - default: - { - printf("unknown Cylinder up axis\n"); - } - - }; - - - - break; - } - case CONE_SHAPE_PROXYTYPE: - { - btConeShapeData* conData = (btConeShapeData*) shapeData; - btVector3 halfExtents = implicitShapeDimensions;//+margin; - switch (conData->m_upIndex) - { - case 0: - { - shape = createConeShapeX(halfExtents.getY(),halfExtents.getX()); - break; - } - case 1: - { - shape = createConeShapeY(halfExtents.getX(),halfExtents.getY()); - break; - } - case 2: - { - shape = createConeShapeZ(halfExtents.getX(),halfExtents.getZ()); - break; - } - default: - { - printf("unknown Cone up axis\n"); - } - - }; - - - - break; - } - case MULTI_SPHERE_SHAPE_PROXYTYPE: - { - btMultiSphereShapeData* mss = (btMultiSphereShapeData*)bsd; - int numSpheres = mss->m_localPositionArraySize; - - btAlignedObjectArray tmpPos; - btAlignedObjectArray radii; - radii.resize(numSpheres); - tmpPos.resize(numSpheres); - int i; - for ( i=0;im_localPositionArrayPtr[i].m_pos); - radii[i] = mss->m_localPositionArrayPtr[i].m_radius; - } - shape = createMultiSphereShape(&tmpPos[0],&radii[0],numSpheres); - break; - } - case CONVEX_HULL_SHAPE_PROXYTYPE: - { - // int sz = sizeof(btConvexHullShapeData); - // int sz2 = sizeof(btConvexInternalShapeData); - // int sz3 = sizeof(btCollisionShapeData); - btConvexHullShapeData* convexData = (btConvexHullShapeData*)bsd; - int numPoints = convexData->m_numUnscaledPoints; - - btAlignedObjectArray tmpPoints; - tmpPoints.resize(numPoints); - int i; - for ( i=0;im_unscaledPointsDoublePtr) - tmpPoints[i].deSerialize(convexData->m_unscaledPointsDoublePtr[i]); - if (convexData->m_unscaledPointsFloatPtr) - tmpPoints[i].deSerializeFloat(convexData->m_unscaledPointsFloatPtr[i]); -#else - if (convexData->m_unscaledPointsFloatPtr) - tmpPoints[i].deSerialize(convexData->m_unscaledPointsFloatPtr[i]); - if (convexData->m_unscaledPointsDoublePtr) - tmpPoints[i].deSerializeDouble(convexData->m_unscaledPointsDoublePtr[i]); -#endif //BT_USE_DOUBLE_PRECISION - } - btConvexHullShape* hullShape = createConvexHullShape(); - for (i=0;iaddPoint(tmpPoints[i]); - } - hullShape->setMargin(bsd->m_collisionMargin); - //hullShape->initializePolyhedralFeatures(); - shape = hullShape; - break; - } - default: - { - printf("error: cannot create shape type (%d)\n",shapeData->m_shapeType); - } - } - - if (shape) - { - shape->setMargin(bsd->m_collisionMargin); - - btVector3 localScaling; - localScaling.deSerializeFloat(bsd->m_localScaling); - shape->setLocalScaling(localScaling); - - } - break; - } - case TRIANGLE_MESH_SHAPE_PROXYTYPE: - { - btTriangleMeshShapeData* trimesh = (btTriangleMeshShapeData*)shapeData; - btStridingMeshInterfaceData* interfaceData = createStridingMeshInterfaceData(&trimesh->m_meshInterface); - btTriangleIndexVertexArray* meshInterface = createMeshInterface(*interfaceData); - if (!meshInterface->getNumSubParts()) - { - return 0; - } - - btVector3 scaling; scaling.deSerializeFloat(trimesh->m_meshInterface.m_scaling); - meshInterface->setScaling(scaling); - - - btOptimizedBvh* bvh = 0; -#if 1 - if (trimesh->m_quantizedFloatBvh) - { - btOptimizedBvh** bvhPtr = m_bvhMap.find(trimesh->m_quantizedFloatBvh); - if (bvhPtr && *bvhPtr) - { - bvh = *bvhPtr; - } else - { - bvh = createOptimizedBvh(); - bvh->deSerializeFloat(*trimesh->m_quantizedFloatBvh); - } - } - if (trimesh->m_quantizedDoubleBvh) - { - btOptimizedBvh** bvhPtr = m_bvhMap.find(trimesh->m_quantizedDoubleBvh); - if (bvhPtr && *bvhPtr) - { - bvh = *bvhPtr; - } else - { - bvh = createOptimizedBvh(); - bvh->deSerializeDouble(*trimesh->m_quantizedDoubleBvh); - } - } -#endif - - - btBvhTriangleMeshShape* trimeshShape = createBvhTriangleMeshShape(meshInterface,bvh); - trimeshShape->setMargin(trimesh->m_collisionMargin); - shape = trimeshShape; - - if (trimesh->m_triangleInfoMap) - { - btTriangleInfoMap* map = createTriangleInfoMap(); - map->deSerialize(*trimesh->m_triangleInfoMap); - trimeshShape->setTriangleInfoMap(map); - -#ifdef USE_INTERNAL_EDGE_UTILITY - gContactAddedCallback = btAdjustInternalEdgeContactsCallback; -#endif //USE_INTERNAL_EDGE_UTILITY - - } - - //printf("trimesh->m_collisionMargin=%f\n",trimesh->m_collisionMargin); - break; - } - case COMPOUND_SHAPE_PROXYTYPE: - { - btCompoundShapeData* compoundData = (btCompoundShapeData*)shapeData; - btCompoundShape* compoundShape = createCompoundShape(); - - - btAlignedObjectArray childShapes; - for (int i=0;im_numChildShapes;i++) - { - - btCollisionShapeData* cd = compoundData->m_childShapePtr[i].m_childShape; - - btCollisionShape* childShape = convertCollisionShape(cd); - if (childShape) - { - btTransform localTransform; - localTransform.deSerializeFloat(compoundData->m_childShapePtr[i].m_transform); - compoundShape->addChildShape(localTransform,childShape); - } else - { -#ifdef _DEBUG - printf("error: couldn't create childShape for compoundShape\n"); -#endif - } - - } - shape = compoundShape; - - break; - } - case SOFTBODY_SHAPE_PROXYTYPE: - { - return 0; - } - default: - { -#ifdef _DEBUG - printf("unsupported shape type (%d)\n",shapeData->m_shapeType); -#endif - } - } - - return shape; - -} - - - -char* btWorldImporter::duplicateName(const char* name) -{ - if (name) - { - int l = (int)strlen(name); - char* newName = new char[l+1]; - memcpy(newName,name,l); - newName[l] = 0; - m_allocatedNames.push_back(newName); - return newName; - } - return 0; -} - -void btWorldImporter::convertConstraintBackwardsCompatible281(btTypedConstraintData* constraintData, btRigidBody* rbA, btRigidBody* rbB, int fileVersion) -{ - - btTypedConstraint* constraint = 0; - - switch (constraintData->m_objectType) - { - case POINT2POINT_CONSTRAINT_TYPE: - { - btPoint2PointConstraintDoubleData* p2pData = (btPoint2PointConstraintDoubleData*)constraintData; - if (rbA && rbB) - { - btVector3 pivotInA,pivotInB; - pivotInA.deSerializeDouble(p2pData->m_pivotInA); - pivotInB.deSerializeDouble(p2pData->m_pivotInB); - constraint = createPoint2PointConstraint(*rbA,*rbB,pivotInA,pivotInB); - } else - { - btVector3 pivotInA; - pivotInA.deSerializeDouble(p2pData->m_pivotInA); - constraint = createPoint2PointConstraint(*rbA,pivotInA); - } - break; - } - case HINGE_CONSTRAINT_TYPE: - { - btHingeConstraint* hinge = 0; - - btHingeConstraintDoubleData* hingeData = (btHingeConstraintDoubleData*)constraintData; - if (rbA&& rbB) - { - btTransform rbAFrame,rbBFrame; - rbAFrame.deSerializeDouble(hingeData->m_rbAFrame); - rbBFrame.deSerializeDouble(hingeData->m_rbBFrame); - hinge = createHingeConstraint(*rbA,*rbB,rbAFrame,rbBFrame,hingeData->m_useReferenceFrameA!=0); - } else - { - btTransform rbAFrame; - rbAFrame.deSerializeDouble(hingeData->m_rbAFrame); - hinge = createHingeConstraint(*rbA,rbAFrame,hingeData->m_useReferenceFrameA!=0); - } - if (hingeData->m_enableAngularMotor) - { - hinge->enableAngularMotor(true,(btScalar)hingeData->m_motorTargetVelocity,(btScalar)hingeData->m_maxMotorImpulse); - } - hinge->setAngularOnly(hingeData->m_angularOnly!=0); - hinge->setLimit(btScalar(hingeData->m_lowerLimit),btScalar(hingeData->m_upperLimit),btScalar(hingeData->m_limitSoftness),btScalar(hingeData->m_biasFactor),btScalar(hingeData->m_relaxationFactor)); - - constraint = hinge; - break; - - } - case CONETWIST_CONSTRAINT_TYPE: - { - btConeTwistConstraintData* coneData = (btConeTwistConstraintData*)constraintData; - btConeTwistConstraint* coneTwist = 0; - - if (rbA&& rbB) - { - btTransform rbAFrame,rbBFrame; - rbAFrame.deSerializeFloat(coneData->m_rbAFrame); - rbBFrame.deSerializeFloat(coneData->m_rbBFrame); - coneTwist = createConeTwistConstraint(*rbA,*rbB,rbAFrame,rbBFrame); - } else - { - btTransform rbAFrame; - rbAFrame.deSerializeFloat(coneData->m_rbAFrame); - coneTwist = createConeTwistConstraint(*rbA,rbAFrame); - } - coneTwist->setLimit((btScalar)coneData->m_swingSpan1,(btScalar)coneData->m_swingSpan2,(btScalar)coneData->m_twistSpan,(btScalar)coneData->m_limitSoftness, - (btScalar)coneData->m_biasFactor,(btScalar)coneData->m_relaxationFactor); - coneTwist->setDamping((btScalar)coneData->m_damping); - - constraint = coneTwist; - break; - } - - case D6_SPRING_CONSTRAINT_TYPE: - { - - btGeneric6DofSpringConstraintData* dofData = (btGeneric6DofSpringConstraintData*)constraintData; - // int sz = sizeof(btGeneric6DofSpringConstraintData); - btGeneric6DofSpringConstraint* dof = 0; - - if (rbA && rbB) - { - btTransform rbAFrame,rbBFrame; - rbAFrame.deSerializeFloat(dofData->m_6dofData.m_rbAFrame); - rbBFrame.deSerializeFloat(dofData->m_6dofData.m_rbBFrame); - dof = createGeneric6DofSpringConstraint(*rbA,*rbB,rbAFrame,rbBFrame,dofData->m_6dofData.m_useLinearReferenceFrameA!=0); - } else - { - printf("Error in btWorldImporter::createGeneric6DofSpringConstraint: requires rbA && rbB\n"); - } - - if (dof) - { - btVector3 angLowerLimit,angUpperLimit, linLowerLimit,linUpperlimit; - angLowerLimit.deSerializeFloat(dofData->m_6dofData.m_angularLowerLimit); - angUpperLimit.deSerializeFloat(dofData->m_6dofData.m_angularUpperLimit); - linLowerLimit.deSerializeFloat(dofData->m_6dofData.m_linearLowerLimit); - linUpperlimit.deSerializeFloat(dofData->m_6dofData.m_linearUpperLimit); - - angLowerLimit.setW(0.f); - dof->setAngularLowerLimit(angLowerLimit); - dof->setAngularUpperLimit(angUpperLimit); - dof->setLinearLowerLimit(linLowerLimit); - dof->setLinearUpperLimit(linUpperlimit); - - int i; - if (fileVersion>280) - { - for (i=0;i<6;i++) - { - dof->setStiffness(i,(btScalar)dofData->m_springStiffness[i]); - dof->setEquilibriumPoint(i,(btScalar)dofData->m_equilibriumPoint[i]); - dof->enableSpring(i,dofData->m_springEnabled[i]!=0); - dof->setDamping(i,(btScalar)dofData->m_springDamping[i]); - } - } - } - - constraint = dof; - break; - - } - case D6_CONSTRAINT_TYPE: - { - btGeneric6DofConstraintData* dofData = (btGeneric6DofConstraintData*)constraintData; - btGeneric6DofConstraint* dof = 0; - - if (rbA&& rbB) - { - btTransform rbAFrame,rbBFrame; - rbAFrame.deSerializeFloat(dofData->m_rbAFrame); - rbBFrame.deSerializeFloat(dofData->m_rbBFrame); - dof = createGeneric6DofConstraint(*rbA,*rbB,rbAFrame,rbBFrame,dofData->m_useLinearReferenceFrameA!=0); - } else - { - if (rbB) - { - btTransform rbBFrame; - rbBFrame.deSerializeFloat(dofData->m_rbBFrame); - dof = createGeneric6DofConstraint(*rbB,rbBFrame,dofData->m_useLinearReferenceFrameA!=0); - } else - { - printf("Error in btWorldImporter::createGeneric6DofConstraint: missing rbB\n"); - } - } - - if (dof) - { - btVector3 angLowerLimit,angUpperLimit, linLowerLimit,linUpperlimit; - angLowerLimit.deSerializeFloat(dofData->m_angularLowerLimit); - angUpperLimit.deSerializeFloat(dofData->m_angularUpperLimit); - linLowerLimit.deSerializeFloat(dofData->m_linearLowerLimit); - linUpperlimit.deSerializeFloat(dofData->m_linearUpperLimit); - - dof->setAngularLowerLimit(angLowerLimit); - dof->setAngularUpperLimit(angUpperLimit); - dof->setLinearLowerLimit(linLowerLimit); - dof->setLinearUpperLimit(linUpperlimit); - } - - constraint = dof; - break; - } - case SLIDER_CONSTRAINT_TYPE: - { - btSliderConstraintData* sliderData = (btSliderConstraintData*)constraintData; - btSliderConstraint* slider = 0; - if (rbA&& rbB) - { - btTransform rbAFrame,rbBFrame; - rbAFrame.deSerializeFloat(sliderData->m_rbAFrame); - rbBFrame.deSerializeFloat(sliderData->m_rbBFrame); - slider = createSliderConstraint(*rbA,*rbB,rbAFrame,rbBFrame,sliderData->m_useLinearReferenceFrameA!=0); - } else - { - btTransform rbBFrame; - rbBFrame.deSerializeFloat(sliderData->m_rbBFrame); - slider = createSliderConstraint(*rbB,rbBFrame,sliderData->m_useLinearReferenceFrameA!=0); - } - slider->setLowerLinLimit((btScalar)sliderData->m_linearLowerLimit); - slider->setUpperLinLimit((btScalar)sliderData->m_linearUpperLimit); - slider->setLowerAngLimit((btScalar)sliderData->m_angularLowerLimit); - slider->setUpperAngLimit((btScalar)sliderData->m_angularUpperLimit); - slider->setUseFrameOffset(sliderData->m_useOffsetForConstraintFrame!=0); - constraint = slider; - break; - } - - default: - { - printf("unknown constraint type\n"); - } - }; - - if (constraint) - { - constraint->setDbgDrawSize((btScalar)constraintData->m_dbgDrawSize); - ///those fields didn't exist and set to zero for pre-280 versions, so do a check here - if (fileVersion>=280) - { - constraint->setBreakingImpulseThreshold((btScalar)constraintData->m_breakingImpulseThreshold); - constraint->setEnabled(constraintData->m_isEnabled!=0); - constraint->setOverrideNumSolverIterations(constraintData->m_overrideNumSolverIterations); - } - - if (constraintData->m_name) - { - char* newname = duplicateName(constraintData->m_name); - m_nameConstraintMap.insert(newname,constraint); - m_objectNameMap.insert(constraint,newname); - } - if(m_dynamicsWorld) - m_dynamicsWorld->addConstraint(constraint,constraintData->m_disableCollisionsBetweenLinkedBodies!=0); - } - -} - -void btWorldImporter::convertConstraintFloat(btTypedConstraintFloatData* constraintData, btRigidBody* rbA, btRigidBody* rbB, int fileVersion) -{ - btTypedConstraint* constraint = 0; - - switch (constraintData->m_objectType) - { - case POINT2POINT_CONSTRAINT_TYPE: - { - btPoint2PointConstraintFloatData* p2pData = (btPoint2PointConstraintFloatData*)constraintData; - if (rbA&& rbB) - { - btVector3 pivotInA,pivotInB; - pivotInA.deSerializeFloat(p2pData->m_pivotInA); - pivotInB.deSerializeFloat(p2pData->m_pivotInB); - constraint = createPoint2PointConstraint(*rbA,*rbB,pivotInA,pivotInB); - - } else - { - btVector3 pivotInA; - pivotInA.deSerializeFloat(p2pData->m_pivotInA); - constraint = createPoint2PointConstraint(*rbA,pivotInA); - } - break; - } - case HINGE_CONSTRAINT_TYPE: - { - btHingeConstraint* hinge = 0; - btHingeConstraintFloatData* hingeData = (btHingeConstraintFloatData*)constraintData; - if (rbA&& rbB) - { - btTransform rbAFrame,rbBFrame; - rbAFrame.deSerializeFloat(hingeData->m_rbAFrame); - rbBFrame.deSerializeFloat(hingeData->m_rbBFrame); - hinge = createHingeConstraint(*rbA,*rbB,rbAFrame,rbBFrame,hingeData->m_useReferenceFrameA!=0); - } else - { - btTransform rbAFrame; - rbAFrame.deSerializeFloat(hingeData->m_rbAFrame); - hinge = createHingeConstraint(*rbA,rbAFrame,hingeData->m_useReferenceFrameA!=0); - } - if (hingeData->m_enableAngularMotor) - { - hinge->enableAngularMotor(true,hingeData->m_motorTargetVelocity,hingeData->m_maxMotorImpulse); - } - hinge->setAngularOnly(hingeData->m_angularOnly!=0); - hinge->setLimit(btScalar(hingeData->m_lowerLimit),btScalar(hingeData->m_upperLimit),btScalar(hingeData->m_limitSoftness),btScalar(hingeData->m_biasFactor),btScalar(hingeData->m_relaxationFactor)); - - constraint = hinge; - break; - - } - case CONETWIST_CONSTRAINT_TYPE: - { - btConeTwistConstraintData* coneData = (btConeTwistConstraintData*)constraintData; - btConeTwistConstraint* coneTwist = 0; - - if (rbA&& rbB) - { - btTransform rbAFrame,rbBFrame; - rbAFrame.deSerializeFloat(coneData->m_rbAFrame); - rbBFrame.deSerializeFloat(coneData->m_rbBFrame); - coneTwist = createConeTwistConstraint(*rbA,*rbB,rbAFrame,rbBFrame); - } else - { - btTransform rbAFrame; - rbAFrame.deSerializeFloat(coneData->m_rbAFrame); - coneTwist = createConeTwistConstraint(*rbA,rbAFrame); - } - coneTwist->setLimit(coneData->m_swingSpan1,coneData->m_swingSpan2,coneData->m_twistSpan,coneData->m_limitSoftness,coneData->m_biasFactor,coneData->m_relaxationFactor); - coneTwist->setDamping(coneData->m_damping); - - constraint = coneTwist; - break; - } - - case D6_SPRING_CONSTRAINT_TYPE: - { - - btGeneric6DofSpringConstraintData* dofData = (btGeneric6DofSpringConstraintData*)constraintData; - // int sz = sizeof(btGeneric6DofSpringConstraintData); - btGeneric6DofSpringConstraint* dof = 0; - - if (rbA && rbB) - { - btTransform rbAFrame,rbBFrame; - rbAFrame.deSerializeFloat(dofData->m_6dofData.m_rbAFrame); - rbBFrame.deSerializeFloat(dofData->m_6dofData.m_rbBFrame); - dof = createGeneric6DofSpringConstraint(*rbA,*rbB,rbAFrame,rbBFrame,dofData->m_6dofData.m_useLinearReferenceFrameA!=0); - } else - { - printf("Error in btWorldImporter::createGeneric6DofSpringConstraint: requires rbA && rbB\n"); - } - - if (dof) - { - btVector3 angLowerLimit,angUpperLimit, linLowerLimit,linUpperlimit; - angLowerLimit.deSerializeFloat(dofData->m_6dofData.m_angularLowerLimit); - angUpperLimit.deSerializeFloat(dofData->m_6dofData.m_angularUpperLimit); - linLowerLimit.deSerializeFloat(dofData->m_6dofData.m_linearLowerLimit); - linUpperlimit.deSerializeFloat(dofData->m_6dofData.m_linearUpperLimit); - - angLowerLimit.setW(0.f); - dof->setAngularLowerLimit(angLowerLimit); - dof->setAngularUpperLimit(angUpperLimit); - dof->setLinearLowerLimit(linLowerLimit); - dof->setLinearUpperLimit(linUpperlimit); - - int i; - if (fileVersion>280) - { - for (i=0;i<6;i++) - { - dof->setStiffness(i,dofData->m_springStiffness[i]); - dof->setEquilibriumPoint(i,dofData->m_equilibriumPoint[i]); - dof->enableSpring(i,dofData->m_springEnabled[i]!=0); - dof->setDamping(i,dofData->m_springDamping[i]); - } - } - } - - constraint = dof; - break; - } - case D6_CONSTRAINT_TYPE: - { - btGeneric6DofConstraintData* dofData = (btGeneric6DofConstraintData*)constraintData; - btGeneric6DofConstraint* dof = 0; - - if (rbA&& rbB) - { - btTransform rbAFrame,rbBFrame; - rbAFrame.deSerializeFloat(dofData->m_rbAFrame); - rbBFrame.deSerializeFloat(dofData->m_rbBFrame); - dof = createGeneric6DofConstraint(*rbA,*rbB,rbAFrame,rbBFrame,dofData->m_useLinearReferenceFrameA!=0); - } else - { - if (rbB) - { - btTransform rbBFrame; - rbBFrame.deSerializeFloat(dofData->m_rbBFrame); - dof = createGeneric6DofConstraint(*rbB,rbBFrame,dofData->m_useLinearReferenceFrameA!=0); - } else - { - printf("Error in btWorldImporter::createGeneric6DofConstraint: missing rbB\n"); - } - } - - if (dof) - { - btVector3 angLowerLimit,angUpperLimit, linLowerLimit,linUpperlimit; - angLowerLimit.deSerializeFloat(dofData->m_angularLowerLimit); - angUpperLimit.deSerializeFloat(dofData->m_angularUpperLimit); - linLowerLimit.deSerializeFloat(dofData->m_linearLowerLimit); - linUpperlimit.deSerializeFloat(dofData->m_linearUpperLimit); - - dof->setAngularLowerLimit(angLowerLimit); - dof->setAngularUpperLimit(angUpperLimit); - dof->setLinearLowerLimit(linLowerLimit); - dof->setLinearUpperLimit(linUpperlimit); - } - - constraint = dof; - break; - } - case SLIDER_CONSTRAINT_TYPE: - { - btSliderConstraintData* sliderData = (btSliderConstraintData*)constraintData; - btSliderConstraint* slider = 0; - if (rbA&& rbB) - { - btTransform rbAFrame,rbBFrame; - rbAFrame.deSerializeFloat(sliderData->m_rbAFrame); - rbBFrame.deSerializeFloat(sliderData->m_rbBFrame); - slider = createSliderConstraint(*rbA,*rbB,rbAFrame,rbBFrame,sliderData->m_useLinearReferenceFrameA!=0); - } else - { - btTransform rbBFrame; - rbBFrame.deSerializeFloat(sliderData->m_rbBFrame); - slider = createSliderConstraint(*rbB,rbBFrame,sliderData->m_useLinearReferenceFrameA!=0); - } - slider->setLowerLinLimit(sliderData->m_linearLowerLimit); - slider->setUpperLinLimit(sliderData->m_linearUpperLimit); - slider->setLowerAngLimit(sliderData->m_angularLowerLimit); - slider->setUpperAngLimit(sliderData->m_angularUpperLimit); - slider->setUseFrameOffset(sliderData->m_useOffsetForConstraintFrame!=0); - constraint = slider; - break; - } - case GEAR_CONSTRAINT_TYPE: - { - btGearConstraintFloatData* gearData = (btGearConstraintFloatData*) constraintData; - btGearConstraint* gear = 0; - if (rbA&&rbB) - { - btVector3 axisInA,axisInB; - axisInA.deSerializeFloat(gearData->m_axisInA); - axisInB.deSerializeFloat(gearData->m_axisInB); - gear = createGearConstraint(*rbA, *rbB, axisInA,axisInB, gearData->m_ratio); - } else - { - btAssert(0); - //perhaps a gear against a 'fixed' body, while the 'fixed' body is not serialized? - //btGearConstraint(btRigidBody& rbA, btRigidBody& rbB, const btVector3& axisInA,const btVector3& axisInB, btScalar ratio=1.f); - } - constraint = gear; - break; - } - case D6_SPRING_2_CONSTRAINT_TYPE: - { - - btGeneric6DofSpring2ConstraintData* dofData = (btGeneric6DofSpring2ConstraintData*)constraintData; - - btGeneric6DofSpring2Constraint* dof = 0; - - if (rbA && rbB) - { - btTransform rbAFrame,rbBFrame; - rbAFrame.deSerializeFloat(dofData->m_rbAFrame); - rbBFrame.deSerializeFloat(dofData->m_rbBFrame); - dof = createGeneric6DofSpring2Constraint(*rbA,*rbB,rbAFrame,rbBFrame, dofData->m_rotateOrder); - } else - { - printf("Error in btWorldImporter::createGeneric6DofSpring2Constraint: requires rbA && rbB\n"); - } - - if (dof) - { - btVector3 angLowerLimit,angUpperLimit, linLowerLimit,linUpperlimit; - angLowerLimit.deSerializeFloat(dofData->m_angularLowerLimit); - angUpperLimit.deSerializeFloat(dofData->m_angularUpperLimit); - linLowerLimit.deSerializeFloat(dofData->m_linearLowerLimit); - linUpperlimit.deSerializeFloat(dofData->m_linearUpperLimit); - - angLowerLimit.setW(0.f); - dof->setAngularLowerLimit(angLowerLimit); - dof->setAngularUpperLimit(angUpperLimit); - dof->setLinearLowerLimit(linLowerLimit); - dof->setLinearUpperLimit(linUpperlimit); - - int i; - if (fileVersion>280) - { - //6-dof: 3 linear followed by 3 angular - for (i=0;i<3;i++) - { - dof->setStiffness(i,dofData->m_linearSpringStiffness.m_floats[i],dofData->m_linearSpringStiffnessLimited[i]!=0); - dof->setEquilibriumPoint(i,dofData->m_linearEquilibriumPoint.m_floats[i]); - dof->enableSpring(i,dofData->m_linearEnableSpring[i]!=0); - dof->setDamping(i,dofData->m_linearSpringDamping.m_floats[i],(dofData->m_linearSpringDampingLimited[i]!=0)); - } - for (i=0;i<3;i++) - { - dof->setStiffness(i+3,dofData->m_angularSpringStiffness.m_floats[i],(dofData->m_angularSpringStiffnessLimited[i]!=0)); - dof->setEquilibriumPoint(i+3,dofData->m_angularEquilibriumPoint.m_floats[i]); - dof->enableSpring(i+3,dofData->m_angularEnableSpring[i]!=0); - dof->setDamping(i+3,dofData->m_angularSpringDamping.m_floats[i],dofData->m_angularSpringDampingLimited[i]); - } - - } - } - - constraint = dof; - break; - - } - case FIXED_CONSTRAINT_TYPE: - { - - btGeneric6DofSpring2Constraint* dof = 0; - if (rbA && rbB) - { - btTransform rbAFrame,rbBFrame; - //compute a shared world frame, and compute frameInA, frameInB relative to this - btTransform sharedFrame; - sharedFrame.setIdentity(); - btVector3 centerPos = btScalar(0.5)*(rbA->getWorldTransform().getOrigin()+ - rbB->getWorldTransform().getOrigin()); - sharedFrame.setOrigin(centerPos); - rbAFrame = rbA->getWorldTransform().inverse()*sharedFrame; - rbBFrame = rbB->getWorldTransform().inverse()*sharedFrame; - - - dof = createGeneric6DofSpring2Constraint(*rbA,*rbB,rbAFrame,rbBFrame, RO_XYZ); - dof->setLinearUpperLimit(btVector3(0,0,0)); - dof->setLinearLowerLimit(btVector3(0,0,0)); - dof->setAngularUpperLimit(btVector3(0,0,0)); - dof->setAngularLowerLimit(btVector3(0,0,0)); - - } else - { - printf("Error in btWorldImporter::createGeneric6DofSpring2Constraint: requires rbA && rbB\n"); - } - - constraint = dof; - break; - } - default: - { - printf("unknown constraint type\n"); - } - }; - - if (constraint) - { - constraint->setDbgDrawSize(constraintData->m_dbgDrawSize); - ///those fields didn't exist and set to zero for pre-280 versions, so do a check here - if (fileVersion>=280) - { - constraint->setBreakingImpulseThreshold(constraintData->m_breakingImpulseThreshold); - constraint->setEnabled(constraintData->m_isEnabled!=0); - constraint->setOverrideNumSolverIterations(constraintData->m_overrideNumSolverIterations); - } - - if (constraintData->m_name) - { - char* newname = duplicateName(constraintData->m_name); - m_nameConstraintMap.insert(newname,constraint); - m_objectNameMap.insert(constraint,newname); - } - if(m_dynamicsWorld) - m_dynamicsWorld->addConstraint(constraint,constraintData->m_disableCollisionsBetweenLinkedBodies!=0); - } - - -} - - - -void btWorldImporter::convertConstraintDouble(btTypedConstraintDoubleData* constraintData, btRigidBody* rbA, btRigidBody* rbB, int fileVersion) -{ - btTypedConstraint* constraint = 0; - - switch (constraintData->m_objectType) - { - case POINT2POINT_CONSTRAINT_TYPE: - { - btPoint2PointConstraintDoubleData2* p2pData = (btPoint2PointConstraintDoubleData2*)constraintData; - if (rbA && rbB) - { - btVector3 pivotInA,pivotInB; - pivotInA.deSerializeDouble(p2pData->m_pivotInA); - pivotInB.deSerializeDouble(p2pData->m_pivotInB); - constraint = createPoint2PointConstraint(*rbA,*rbB,pivotInA,pivotInB); - } else - { - btVector3 pivotInA; - pivotInA.deSerializeDouble(p2pData->m_pivotInA); - constraint = createPoint2PointConstraint(*rbA,pivotInA); - } - break; - } - case HINGE_CONSTRAINT_TYPE: - { - btHingeConstraint* hinge = 0; - - btHingeConstraintDoubleData2* hingeData = (btHingeConstraintDoubleData2*)constraintData; - if (rbA&& rbB) - { - btTransform rbAFrame,rbBFrame; - rbAFrame.deSerializeDouble(hingeData->m_rbAFrame); - rbBFrame.deSerializeDouble(hingeData->m_rbBFrame); - hinge = createHingeConstraint(*rbA,*rbB,rbAFrame,rbBFrame,hingeData->m_useReferenceFrameA!=0); - } else - { - btTransform rbAFrame; - rbAFrame.deSerializeDouble(hingeData->m_rbAFrame); - hinge = createHingeConstraint(*rbA,rbAFrame,hingeData->m_useReferenceFrameA!=0); - } - if (hingeData->m_enableAngularMotor) - { - hinge->enableAngularMotor(true,(btScalar)hingeData->m_motorTargetVelocity,(btScalar)hingeData->m_maxMotorImpulse); - } - hinge->setAngularOnly(hingeData->m_angularOnly!=0); - hinge->setLimit(btScalar(hingeData->m_lowerLimit),btScalar(hingeData->m_upperLimit),btScalar(hingeData->m_limitSoftness),btScalar(hingeData->m_biasFactor),btScalar(hingeData->m_relaxationFactor)); - - constraint = hinge; - break; - - } - case CONETWIST_CONSTRAINT_TYPE: - { - btConeTwistConstraintDoubleData* coneData = (btConeTwistConstraintDoubleData*)constraintData; - btConeTwistConstraint* coneTwist = 0; - - if (rbA&& rbB) - { - btTransform rbAFrame,rbBFrame; - rbAFrame.deSerializeDouble(coneData->m_rbAFrame); - rbBFrame.deSerializeDouble(coneData->m_rbBFrame); - coneTwist = createConeTwistConstraint(*rbA,*rbB,rbAFrame,rbBFrame); - } else - { - btTransform rbAFrame; - rbAFrame.deSerializeDouble(coneData->m_rbAFrame); - coneTwist = createConeTwistConstraint(*rbA,rbAFrame); - } - coneTwist->setLimit((btScalar)coneData->m_swingSpan1,(btScalar)coneData->m_swingSpan2,(btScalar)coneData->m_twistSpan,(btScalar)coneData->m_limitSoftness, - (btScalar)coneData->m_biasFactor,(btScalar)coneData->m_relaxationFactor); - coneTwist->setDamping((btScalar)coneData->m_damping); - - constraint = coneTwist; - break; - } - - case D6_SPRING_CONSTRAINT_TYPE: - { - - btGeneric6DofSpringConstraintDoubleData2* dofData = (btGeneric6DofSpringConstraintDoubleData2*)constraintData; - // int sz = sizeof(btGeneric6DofSpringConstraintData); - btGeneric6DofSpringConstraint* dof = 0; - - if (rbA && rbB) - { - btTransform rbAFrame,rbBFrame; - rbAFrame.deSerializeDouble(dofData->m_6dofData.m_rbAFrame); - rbBFrame.deSerializeDouble(dofData->m_6dofData.m_rbBFrame); - dof = createGeneric6DofSpringConstraint(*rbA,*rbB,rbAFrame,rbBFrame,dofData->m_6dofData.m_useLinearReferenceFrameA!=0); - } else - { - printf("Error in btWorldImporter::createGeneric6DofSpringConstraint: requires rbA && rbB\n"); - } - - if (dof) - { - btVector3 angLowerLimit,angUpperLimit, linLowerLimit,linUpperlimit; - angLowerLimit.deSerializeDouble(dofData->m_6dofData.m_angularLowerLimit); - angUpperLimit.deSerializeDouble(dofData->m_6dofData.m_angularUpperLimit); - linLowerLimit.deSerializeDouble(dofData->m_6dofData.m_linearLowerLimit); - linUpperlimit.deSerializeDouble(dofData->m_6dofData.m_linearUpperLimit); - - angLowerLimit.setW(0.f); - dof->setAngularLowerLimit(angLowerLimit); - dof->setAngularUpperLimit(angUpperLimit); - dof->setLinearLowerLimit(linLowerLimit); - dof->setLinearUpperLimit(linUpperlimit); - - int i; - if (fileVersion>280) - { - for (i=0;i<6;i++) - { - dof->setStiffness(i,(btScalar)dofData->m_springStiffness[i]); - dof->setEquilibriumPoint(i,(btScalar)dofData->m_equilibriumPoint[i]); - dof->enableSpring(i,dofData->m_springEnabled[i]!=0); - dof->setDamping(i,(btScalar)dofData->m_springDamping[i]); - } - } - } - - constraint = dof; - break; - } - case D6_CONSTRAINT_TYPE: - { - btGeneric6DofConstraintDoubleData2* dofData = (btGeneric6DofConstraintDoubleData2*)constraintData; - btGeneric6DofConstraint* dof = 0; - - if (rbA&& rbB) - { - btTransform rbAFrame,rbBFrame; - rbAFrame.deSerializeDouble(dofData->m_rbAFrame); - rbBFrame.deSerializeDouble(dofData->m_rbBFrame); - dof = createGeneric6DofConstraint(*rbA,*rbB,rbAFrame,rbBFrame,dofData->m_useLinearReferenceFrameA!=0); - } else - { - if (rbB) - { - btTransform rbBFrame; - rbBFrame.deSerializeDouble(dofData->m_rbBFrame); - dof = createGeneric6DofConstraint(*rbB,rbBFrame,dofData->m_useLinearReferenceFrameA!=0); - } else - { - printf("Error in btWorldImporter::createGeneric6DofConstraint: missing rbB\n"); - } - } - - if (dof) - { - btVector3 angLowerLimit,angUpperLimit, linLowerLimit,linUpperlimit; - angLowerLimit.deSerializeDouble(dofData->m_angularLowerLimit); - angUpperLimit.deSerializeDouble(dofData->m_angularUpperLimit); - linLowerLimit.deSerializeDouble(dofData->m_linearLowerLimit); - linUpperlimit.deSerializeDouble(dofData->m_linearUpperLimit); - - dof->setAngularLowerLimit(angLowerLimit); - dof->setAngularUpperLimit(angUpperLimit); - dof->setLinearLowerLimit(linLowerLimit); - dof->setLinearUpperLimit(linUpperlimit); - } - - constraint = dof; - break; - } - case SLIDER_CONSTRAINT_TYPE: - { - btSliderConstraintDoubleData* sliderData = (btSliderConstraintDoubleData*)constraintData; - btSliderConstraint* slider = 0; - if (rbA&& rbB) - { - btTransform rbAFrame,rbBFrame; - rbAFrame.deSerializeDouble(sliderData->m_rbAFrame); - rbBFrame.deSerializeDouble(sliderData->m_rbBFrame); - slider = createSliderConstraint(*rbA,*rbB,rbAFrame,rbBFrame,sliderData->m_useLinearReferenceFrameA!=0); - } else - { - btTransform rbBFrame; - rbBFrame.deSerializeDouble(sliderData->m_rbBFrame); - slider = createSliderConstraint(*rbB,rbBFrame,sliderData->m_useLinearReferenceFrameA!=0); - } - slider->setLowerLinLimit((btScalar)sliderData->m_linearLowerLimit); - slider->setUpperLinLimit((btScalar)sliderData->m_linearUpperLimit); - slider->setLowerAngLimit((btScalar)sliderData->m_angularLowerLimit); - slider->setUpperAngLimit((btScalar)sliderData->m_angularUpperLimit); - slider->setUseFrameOffset(sliderData->m_useOffsetForConstraintFrame!=0); - constraint = slider; - break; - } - case GEAR_CONSTRAINT_TYPE: - { - btGearConstraintDoubleData* gearData = (btGearConstraintDoubleData*) constraintData; - btGearConstraint* gear = 0; - if (rbA&&rbB) - { - btVector3 axisInA,axisInB; - axisInA.deSerializeDouble(gearData->m_axisInA); - axisInB.deSerializeDouble(gearData->m_axisInB); - gear = createGearConstraint(*rbA, *rbB, axisInA,axisInB, gearData->m_ratio); - } else - { - btAssert(0); - //perhaps a gear against a 'fixed' body, while the 'fixed' body is not serialized? - //btGearConstraint(btRigidBody& rbA, btRigidBody& rbB, const btVector3& axisInA,const btVector3& axisInB, btScalar ratio=1.f); - } - constraint = gear; - break; - } - - case D6_SPRING_2_CONSTRAINT_TYPE: - { - - btGeneric6DofSpring2ConstraintDoubleData2* dofData = (btGeneric6DofSpring2ConstraintDoubleData2*)constraintData; - - btGeneric6DofSpring2Constraint* dof = 0; - - if (rbA && rbB) - { - btTransform rbAFrame,rbBFrame; - rbAFrame.deSerializeDouble(dofData->m_rbAFrame); - rbBFrame.deSerializeDouble(dofData->m_rbBFrame); - dof = createGeneric6DofSpring2Constraint(*rbA,*rbB,rbAFrame,rbBFrame, dofData->m_rotateOrder); - } else - { - printf("Error in btWorldImporter::createGeneric6DofSpring2Constraint: requires rbA && rbB\n"); - } - - if (dof) - { - btVector3 angLowerLimit,angUpperLimit, linLowerLimit,linUpperlimit; - angLowerLimit.deSerializeDouble(dofData->m_angularLowerLimit); - angUpperLimit.deSerializeDouble(dofData->m_angularUpperLimit); - linLowerLimit.deSerializeDouble(dofData->m_linearLowerLimit); - linUpperlimit.deSerializeDouble(dofData->m_linearUpperLimit); - - angLowerLimit.setW(0.f); - dof->setAngularLowerLimit(angLowerLimit); - dof->setAngularUpperLimit(angUpperLimit); - dof->setLinearLowerLimit(linLowerLimit); - dof->setLinearUpperLimit(linUpperlimit); - - int i; - if (fileVersion>280) - { - //6-dof: 3 linear followed by 3 angular - for (i=0;i<3;i++) - { - dof->setStiffness(i,dofData->m_linearSpringStiffness.m_floats[i],dofData->m_linearSpringStiffnessLimited[i]); - dof->setEquilibriumPoint(i,dofData->m_linearEquilibriumPoint.m_floats[i]); - dof->enableSpring(i,dofData->m_linearEnableSpring[i]!=0); - dof->setDamping(i,dofData->m_linearSpringDamping.m_floats[i],(dofData->m_linearSpringDampingLimited[i]!=0)); - } - for (i=0;i<3;i++) - { - dof->setStiffness(i+3,dofData->m_angularSpringStiffness.m_floats[i],(dofData->m_angularSpringStiffnessLimited[i]!=0)); - dof->setEquilibriumPoint(i+3,dofData->m_angularEquilibriumPoint.m_floats[i]); - dof->enableSpring(i+3,dofData->m_angularEnableSpring[i]!=0); - dof->setDamping(i+3,dofData->m_angularSpringDamping.m_floats[i],(dofData->m_angularSpringDampingLimited[i]!=0)); - } - - } - } - - constraint = dof; - break; - - } - case FIXED_CONSTRAINT_TYPE: - { - - btGeneric6DofSpring2Constraint* dof = 0; - if (rbA && rbB) - { - btTransform rbAFrame,rbBFrame; - //compute a shared world frame, and compute frameInA, frameInB relative to this - btTransform sharedFrame; - sharedFrame.setIdentity(); - btVector3 centerPos = btScalar(0.5)*(rbA->getWorldTransform().getOrigin()+ - rbB->getWorldTransform().getOrigin()); - sharedFrame.setOrigin(centerPos); - rbAFrame = rbA->getWorldTransform().inverse()*sharedFrame; - rbBFrame = rbB->getWorldTransform().inverse()*sharedFrame; - - - dof = createGeneric6DofSpring2Constraint(*rbA,*rbB,rbAFrame,rbBFrame, RO_XYZ); - dof->setLinearUpperLimit(btVector3(0,0,0)); - dof->setLinearLowerLimit(btVector3(0,0,0)); - dof->setAngularUpperLimit(btVector3(0,0,0)); - dof->setAngularLowerLimit(btVector3(0,0,0)); - - } else - { - printf("Error in btWorldImporter::createGeneric6DofSpring2Constraint: requires rbA && rbB\n"); - } - - constraint = dof; - break; - } - - default: - { - printf("unknown constraint type\n"); - } - }; - - if (constraint) - { - constraint->setDbgDrawSize((btScalar)constraintData->m_dbgDrawSize); - ///those fields didn't exist and set to zero for pre-280 versions, so do a check here - if (fileVersion>=280) - { - constraint->setBreakingImpulseThreshold((btScalar)constraintData->m_breakingImpulseThreshold); - constraint->setEnabled(constraintData->m_isEnabled!=0); - constraint->setOverrideNumSolverIterations(constraintData->m_overrideNumSolverIterations); - } - - if (constraintData->m_name) - { - char* newname = duplicateName(constraintData->m_name); - m_nameConstraintMap.insert(newname,constraint); - m_objectNameMap.insert(constraint,newname); - } - if(m_dynamicsWorld) - m_dynamicsWorld->addConstraint(constraint,constraintData->m_disableCollisionsBetweenLinkedBodies!=0); - } - - -} - - - - - - - - - - -btTriangleIndexVertexArray* btWorldImporter::createMeshInterface(btStridingMeshInterfaceData& meshData) -{ - btTriangleIndexVertexArray* meshInterface = createTriangleMeshContainer(); - - for (int i=0;iaddIndexedMesh(meshPart,meshPart.m_indexType); - } - } - - return meshInterface; -} - - -btStridingMeshInterfaceData* btWorldImporter::createStridingMeshInterfaceData(btStridingMeshInterfaceData* interfaceData) -{ - //create a new btStridingMeshInterfaceData that is an exact copy of shapedata and store it in the WorldImporter - btStridingMeshInterfaceData* newData = new btStridingMeshInterfaceData; - - newData->m_scaling = interfaceData->m_scaling; - newData->m_numMeshParts = interfaceData->m_numMeshParts; - newData->m_meshPartsPtr = new btMeshPartData[newData->m_numMeshParts]; - - for(int i = 0;i < newData->m_numMeshParts;i++) - { - btMeshPartData* curPart = &interfaceData->m_meshPartsPtr[i]; - btMeshPartData* curNewPart = &newData->m_meshPartsPtr[i]; - - curNewPart->m_numTriangles = curPart->m_numTriangles; - curNewPart->m_numVertices = curPart->m_numVertices; - - if(curPart->m_vertices3f) - { - curNewPart->m_vertices3f = new btVector3FloatData[curNewPart->m_numVertices]; - memcpy(curNewPart->m_vertices3f,curPart->m_vertices3f,sizeof(btVector3FloatData) * curNewPart->m_numVertices); - } - else - curNewPart->m_vertices3f = NULL; - - if(curPart->m_vertices3d) - { - curNewPart->m_vertices3d = new btVector3DoubleData[curNewPart->m_numVertices]; - memcpy(curNewPart->m_vertices3d,curPart->m_vertices3d,sizeof(btVector3DoubleData) * curNewPart->m_numVertices); - } - else - curNewPart->m_vertices3d = NULL; - - int numIndices = curNewPart->m_numTriangles * 3; - ///the m_3indices8 was not initialized in some Bullet versions, this can cause crashes at loading time - ///we catch it by only dealing with m_3indices8 if none of the other indices are initialized - bool uninitialized3indices8Workaround =false; - - if(curPart->m_indices32) - { - uninitialized3indices8Workaround=true; - curNewPart->m_indices32 = new btIntIndexData[numIndices]; - memcpy(curNewPart->m_indices32,curPart->m_indices32,sizeof(btIntIndexData) * numIndices); - } - else - curNewPart->m_indices32 = NULL; - - if(curPart->m_3indices16) - { - uninitialized3indices8Workaround=true; - curNewPart->m_3indices16 = new btShortIntIndexTripletData[curNewPart->m_numTriangles]; - memcpy(curNewPart->m_3indices16,curPart->m_3indices16,sizeof(btShortIntIndexTripletData) * curNewPart->m_numTriangles); - } - else - curNewPart->m_3indices16 = NULL; - - if(curPart->m_indices16) - { - uninitialized3indices8Workaround=true; - curNewPart->m_indices16 = new btShortIntIndexData[numIndices]; - memcpy(curNewPart->m_indices16,curPart->m_indices16,sizeof(btShortIntIndexData) * numIndices); - } - else - curNewPart->m_indices16 = NULL; - - if(!uninitialized3indices8Workaround && curPart->m_3indices8) - { - curNewPart->m_3indices8 = new btCharIndexTripletData[curNewPart->m_numTriangles]; - memcpy(curNewPart->m_3indices8,curPart->m_3indices8,sizeof(btCharIndexTripletData) * curNewPart->m_numTriangles); - } - else - curNewPart->m_3indices8 = NULL; - - } - - m_allocatedbtStridingMeshInterfaceDatas.push_back(newData); - - return(newData); -} - -#ifdef USE_INTERNAL_EDGE_UTILITY -extern ContactAddedCallback gContactAddedCallback; - -static bool btAdjustInternalEdgeContactsCallback(btManifoldPoint& cp, const btCollisionObject* colObj0,int partId0,int index0,const btCollisionObject* colObj1,int partId1,int index1) -{ - - btAdjustInternalEdgeContacts(cp,colObj1,colObj0, partId1,index1); - //btAdjustInternalEdgeContacts(cp,colObj1,colObj0, partId1,index1, BT_TRIANGLE_CONVEX_BACKFACE_MODE); - //btAdjustInternalEdgeContacts(cp,colObj1,colObj0, partId1,index1, BT_TRIANGLE_CONVEX_DOUBLE_SIDED+BT_TRIANGLE_CONCAVE_DOUBLE_SIDED); - return true; -} -#endif //USE_INTERNAL_EDGE_UTILITY - - - - -btCollisionObject* btWorldImporter::createCollisionObject(const btTransform& startTransform,btCollisionShape* shape, const char* bodyName) -{ - return createRigidBody(false,0,startTransform,shape,bodyName); -} - -void btWorldImporter::setDynamicsWorldInfo(const btVector3& gravity, const btContactSolverInfo& solverInfo) -{ - if (m_dynamicsWorld) - { - m_dynamicsWorld->setGravity(gravity); - m_dynamicsWorld->getSolverInfo() = solverInfo; - } - -} - -btRigidBody* btWorldImporter::createRigidBody(bool isDynamic, btScalar mass, const btTransform& startTransform,btCollisionShape* shape,const char* bodyName) -{ - btVector3 localInertia; - localInertia.setZero(); - - if (mass) - shape->calculateLocalInertia(mass,localInertia); - - btRigidBody* body = new btRigidBody(mass,0,shape,localInertia); - body->setWorldTransform(startTransform); - - if (m_dynamicsWorld) - m_dynamicsWorld->addRigidBody(body); - - if (bodyName) - { - char* newname = duplicateName(bodyName); - m_objectNameMap.insert(body,newname); - m_nameBodyMap.insert(newname,body); - } - m_allocatedRigidBodies.push_back(body); - return body; - -} - -btCollisionShape* btWorldImporter::createPlaneShape(const btVector3& planeNormal,btScalar planeConstant) -{ - btStaticPlaneShape* shape = new btStaticPlaneShape(planeNormal,planeConstant); - m_allocatedCollisionShapes.push_back(shape); - return shape; -} -btCollisionShape* btWorldImporter::createBoxShape(const btVector3& halfExtents) -{ - btBoxShape* shape = new btBoxShape(halfExtents); - m_allocatedCollisionShapes.push_back(shape); - return shape; -} -btCollisionShape* btWorldImporter::createSphereShape(btScalar radius) -{ - btSphereShape* shape = new btSphereShape(radius); - m_allocatedCollisionShapes.push_back(shape); - return shape; -} - - -btCollisionShape* btWorldImporter::createCapsuleShapeX(btScalar radius, btScalar height) -{ - btCapsuleShapeX* shape = new btCapsuleShapeX(radius,height); - m_allocatedCollisionShapes.push_back(shape); - return shape; -} - -btCollisionShape* btWorldImporter::createCapsuleShapeY(btScalar radius, btScalar height) -{ - btCapsuleShape* shape = new btCapsuleShape(radius,height); - m_allocatedCollisionShapes.push_back(shape); - return shape; -} - -btCollisionShape* btWorldImporter::createCapsuleShapeZ(btScalar radius, btScalar height) -{ - btCapsuleShapeZ* shape = new btCapsuleShapeZ(radius,height); - m_allocatedCollisionShapes.push_back(shape); - return shape; -} - -btCollisionShape* btWorldImporter::createCylinderShapeX(btScalar radius,btScalar height) -{ - btCylinderShapeX* shape = new btCylinderShapeX(btVector3(height,radius,radius)); - m_allocatedCollisionShapes.push_back(shape); - return shape; -} - -btCollisionShape* btWorldImporter::createCylinderShapeY(btScalar radius,btScalar height) -{ - btCylinderShape* shape = new btCylinderShape(btVector3(radius,height,radius)); - m_allocatedCollisionShapes.push_back(shape); - return shape; -} - -btCollisionShape* btWorldImporter::createCylinderShapeZ(btScalar radius,btScalar height) -{ - btCylinderShapeZ* shape = new btCylinderShapeZ(btVector3(radius,radius,height)); - m_allocatedCollisionShapes.push_back(shape); - return shape; -} - -btCollisionShape* btWorldImporter::createConeShapeX(btScalar radius,btScalar height) -{ - btConeShapeX* shape = new btConeShapeX(radius,height); - m_allocatedCollisionShapes.push_back(shape); - return shape; -} - -btCollisionShape* btWorldImporter::createConeShapeY(btScalar radius,btScalar height) -{ - btConeShape* shape = new btConeShape(radius,height); - m_allocatedCollisionShapes.push_back(shape); - return shape; -} - -btCollisionShape* btWorldImporter::createConeShapeZ(btScalar radius,btScalar height) -{ - btConeShapeZ* shape = new btConeShapeZ(radius,height); - m_allocatedCollisionShapes.push_back(shape); - return shape; -} - -btTriangleIndexVertexArray* btWorldImporter::createTriangleMeshContainer() -{ - btTriangleIndexVertexArray* in = new btTriangleIndexVertexArray(); - m_allocatedTriangleIndexArrays.push_back(in); - return in; -} - -btOptimizedBvh* btWorldImporter::createOptimizedBvh() -{ - btOptimizedBvh* bvh = new btOptimizedBvh(); - m_allocatedBvhs.push_back(bvh); - return bvh; -} - - -btTriangleInfoMap* btWorldImporter::createTriangleInfoMap() -{ - btTriangleInfoMap* tim = new btTriangleInfoMap(); - m_allocatedTriangleInfoMaps.push_back(tim); - return tim; -} - -btBvhTriangleMeshShape* btWorldImporter::createBvhTriangleMeshShape(btStridingMeshInterface* trimesh, btOptimizedBvh* bvh) -{ - if (bvh) - { - btBvhTriangleMeshShape* bvhTriMesh = new btBvhTriangleMeshShape(trimesh,bvh->isQuantized(), false); - bvhTriMesh->setOptimizedBvh(bvh); - m_allocatedCollisionShapes.push_back(bvhTriMesh); - return bvhTriMesh; - } - - btBvhTriangleMeshShape* ts = new btBvhTriangleMeshShape(trimesh,true); - m_allocatedCollisionShapes.push_back(ts); - return ts; - -} -btCollisionShape* btWorldImporter::createConvexTriangleMeshShape(btStridingMeshInterface* trimesh) -{ - return 0; -} -btGImpactMeshShape* btWorldImporter::createGimpactShape(btStridingMeshInterface* trimesh) -{ -#ifdef USE_GIMPACT - btGImpactMeshShape* shape = new btGImpactMeshShape(trimesh); - m_allocatedCollisionShapes.push_back(shape); - return shape; -#else - return 0; -#endif - -} -btConvexHullShape* btWorldImporter::createConvexHullShape() -{ - btConvexHullShape* shape = new btConvexHullShape(); - m_allocatedCollisionShapes.push_back(shape); - return shape; -} - -btCompoundShape* btWorldImporter::createCompoundShape() -{ - btCompoundShape* shape = new btCompoundShape(); - m_allocatedCollisionShapes.push_back(shape); - return shape; -} - - -btScaledBvhTriangleMeshShape* btWorldImporter::createScaledTrangleMeshShape(btBvhTriangleMeshShape* meshShape,const btVector3& localScaling) -{ - btScaledBvhTriangleMeshShape* shape = new btScaledBvhTriangleMeshShape(meshShape,localScaling); - m_allocatedCollisionShapes.push_back(shape); - return shape; -} - -btMultiSphereShape* btWorldImporter::createMultiSphereShape(const btVector3* positions,const btScalar* radi,int numSpheres) -{ - btMultiSphereShape* shape = new btMultiSphereShape(positions, radi, numSpheres); - m_allocatedCollisionShapes.push_back(shape); - return shape; -} - -btRigidBody& btWorldImporter::getFixedBody() -{ - static btRigidBody s_fixed(0, 0,0); - s_fixed.setMassProps(btScalar(0.),btVector3(btScalar(0.),btScalar(0.),btScalar(0.))); - return s_fixed; -} - -btPoint2PointConstraint* btWorldImporter::createPoint2PointConstraint(btRigidBody& rbA,btRigidBody& rbB, const btVector3& pivotInA,const btVector3& pivotInB) -{ - btPoint2PointConstraint* p2p = new btPoint2PointConstraint(rbA,rbB,pivotInA,pivotInB); - m_allocatedConstraints.push_back(p2p); - return p2p; -} - -btPoint2PointConstraint* btWorldImporter::createPoint2PointConstraint(btRigidBody& rbA,const btVector3& pivotInA) -{ - btPoint2PointConstraint* p2p = new btPoint2PointConstraint(rbA,pivotInA); - m_allocatedConstraints.push_back(p2p); - return p2p; -} - - -btHingeConstraint* btWorldImporter::createHingeConstraint(btRigidBody& rbA,btRigidBody& rbB, const btTransform& rbAFrame, const btTransform& rbBFrame, bool useReferenceFrameA) -{ - btHingeConstraint* hinge = new btHingeConstraint(rbA,rbB,rbAFrame,rbBFrame,useReferenceFrameA); - m_allocatedConstraints.push_back(hinge); - return hinge; -} - -btHingeConstraint* btWorldImporter::createHingeConstraint(btRigidBody& rbA,const btTransform& rbAFrame, bool useReferenceFrameA) -{ - btHingeConstraint* hinge = new btHingeConstraint(rbA,rbAFrame,useReferenceFrameA); - m_allocatedConstraints.push_back(hinge); - return hinge; -} - -btConeTwistConstraint* btWorldImporter::createConeTwistConstraint(btRigidBody& rbA,btRigidBody& rbB,const btTransform& rbAFrame, const btTransform& rbBFrame) -{ - btConeTwistConstraint* cone = new btConeTwistConstraint(rbA,rbB,rbAFrame,rbBFrame); - m_allocatedConstraints.push_back(cone); - return cone; -} - -btConeTwistConstraint* btWorldImporter::createConeTwistConstraint(btRigidBody& rbA,const btTransform& rbAFrame) -{ - btConeTwistConstraint* cone = new btConeTwistConstraint(rbA,rbAFrame); - m_allocatedConstraints.push_back(cone); - return cone; -} - - -btGeneric6DofConstraint* btWorldImporter::createGeneric6DofConstraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& frameInA, const btTransform& frameInB ,bool useLinearReferenceFrameA) -{ - btGeneric6DofConstraint* dof = new btGeneric6DofConstraint(rbA,rbB,frameInA,frameInB,useLinearReferenceFrameA); - m_allocatedConstraints.push_back(dof); - return dof; -} - -btGeneric6DofConstraint* btWorldImporter::createGeneric6DofConstraint(btRigidBody& rbB, const btTransform& frameInB, bool useLinearReferenceFrameB) -{ - btGeneric6DofConstraint* dof = new btGeneric6DofConstraint(rbB,frameInB,useLinearReferenceFrameB); - m_allocatedConstraints.push_back(dof); - return dof; -} - -btGeneric6DofSpring2Constraint* btWorldImporter::createGeneric6DofSpring2Constraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& frameInA, const btTransform& frameInB, int rotateOrder) -{ - btGeneric6DofSpring2Constraint* dof = new btGeneric6DofSpring2Constraint(rbA,rbB,frameInA,frameInB, (RotateOrder)rotateOrder); - m_allocatedConstraints.push_back(dof); - return dof; -} - - - -btGeneric6DofSpringConstraint* btWorldImporter::createGeneric6DofSpringConstraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& frameInA, const btTransform& frameInB ,bool useLinearReferenceFrameA) -{ - btGeneric6DofSpringConstraint* dof = new btGeneric6DofSpringConstraint(rbA,rbB,frameInA,frameInB,useLinearReferenceFrameA); - m_allocatedConstraints.push_back(dof); - return dof; -} - - -btSliderConstraint* btWorldImporter::createSliderConstraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& frameInA, const btTransform& frameInB ,bool useLinearReferenceFrameA) -{ - btSliderConstraint* slider = new btSliderConstraint(rbA,rbB,frameInA,frameInB,useLinearReferenceFrameA); - m_allocatedConstraints.push_back(slider); - return slider; -} - -btSliderConstraint* btWorldImporter::createSliderConstraint(btRigidBody& rbB, const btTransform& frameInB, bool useLinearReferenceFrameA) -{ - btSliderConstraint* slider = new btSliderConstraint(rbB,frameInB,useLinearReferenceFrameA); - m_allocatedConstraints.push_back(slider); - return slider; -} - -btGearConstraint* btWorldImporter::createGearConstraint(btRigidBody& rbA, btRigidBody& rbB, const btVector3& axisInA,const btVector3& axisInB, btScalar ratio) -{ - btGearConstraint* gear = new btGearConstraint(rbA,rbB,axisInA,axisInB,ratio); - m_allocatedConstraints.push_back(gear); - return gear; -} - - // query for data -int btWorldImporter::getNumCollisionShapes() const -{ - return m_allocatedCollisionShapes.size(); -} - -btCollisionShape* btWorldImporter::getCollisionShapeByIndex(int index) -{ - return m_allocatedCollisionShapes[index]; -} - -btCollisionShape* btWorldImporter::getCollisionShapeByName(const char* name) -{ - btCollisionShape** shapePtr = m_nameShapeMap.find(name); - if (shapePtr&& *shapePtr) - { - return *shapePtr; - } - return 0; -} - -btRigidBody* btWorldImporter::getRigidBodyByName(const char* name) -{ - btRigidBody** bodyPtr = m_nameBodyMap.find(name); - if (bodyPtr && *bodyPtr) - { - return *bodyPtr; - } - return 0; -} - -btTypedConstraint* btWorldImporter::getConstraintByName(const char* name) -{ - btTypedConstraint** constraintPtr = m_nameConstraintMap.find(name); - if (constraintPtr && *constraintPtr) - { - return *constraintPtr; - } - return 0; -} - -const char* btWorldImporter::getNameForPointer(const void* ptr) const -{ - const char*const * namePtr = m_objectNameMap.find(ptr); - if (namePtr && *namePtr) - return *namePtr; - return 0; -} - - -int btWorldImporter::getNumRigidBodies() const -{ - return m_allocatedRigidBodies.size(); -} - -btCollisionObject* btWorldImporter::getRigidBodyByIndex(int index) const -{ - return m_allocatedRigidBodies[index]; -} -int btWorldImporter::getNumConstraints() const -{ - return m_allocatedConstraints.size(); -} - -btTypedConstraint* btWorldImporter::getConstraintByIndex(int index) const -{ - return m_allocatedConstraints[index]; -} - -int btWorldImporter::getNumBvhs() const -{ - return m_allocatedBvhs.size(); -} - btOptimizedBvh* btWorldImporter::getBvhByIndex(int index) const -{ - return m_allocatedBvhs[index]; -} - -int btWorldImporter::getNumTriangleInfoMaps() const -{ - return m_allocatedTriangleInfoMaps.size(); -} - -btTriangleInfoMap* btWorldImporter::getTriangleInfoMapByIndex(int index) const -{ - return m_allocatedTriangleInfoMaps[index]; -} - - -void btWorldImporter::convertRigidBodyFloat( btRigidBodyFloatData* colObjData) -{ - btScalar mass = btScalar(colObjData->m_inverseMass? 1.f/colObjData->m_inverseMass : 0.f); - btVector3 localInertia; - localInertia.setZero(); - btCollisionShape** shapePtr = m_shapeMap.find(colObjData->m_collisionObjectData.m_collisionShape); - if (shapePtr && *shapePtr) - { - btTransform startTransform; - colObjData->m_collisionObjectData.m_worldTransform.m_origin.m_floats[3] = 0.f; - startTransform.deSerializeFloat(colObjData->m_collisionObjectData.m_worldTransform); - - // startTransform.setBasis(btMatrix3x3::getIdentity()); - btCollisionShape* shape = (btCollisionShape*)*shapePtr; - if (shape->isNonMoving()) - { - mass = 0.f; - } - if (mass) - { - shape->calculateLocalInertia(mass,localInertia); - } - bool isDynamic = mass!=0.f; - btRigidBody* body = createRigidBody(isDynamic,mass,startTransform,shape,colObjData->m_collisionObjectData.m_name); - body->setFriction(colObjData->m_collisionObjectData.m_friction); - body->setRestitution(colObjData->m_collisionObjectData.m_restitution); - btVector3 linearFactor,angularFactor; - linearFactor.deSerializeFloat(colObjData->m_linearFactor); - angularFactor.deSerializeFloat(colObjData->m_angularFactor); - body->setLinearFactor(linearFactor); - body->setAngularFactor(angularFactor); - -#ifdef USE_INTERNAL_EDGE_UTILITY - if (shape->getShapeType() == TRIANGLE_MESH_SHAPE_PROXYTYPE) - { - btBvhTriangleMeshShape* trimesh = (btBvhTriangleMeshShape*)shape; - if (trimesh->getTriangleInfoMap()) - { - body->setCollisionFlags(body->getCollisionFlags() | btCollisionObject::CF_CUSTOM_MATERIAL_CALLBACK); - } - } -#endif //USE_INTERNAL_EDGE_UTILITY - m_bodyMap.insert(colObjData,body); - } else - { - printf("error: no shape found\n"); - } -} - -void btWorldImporter::convertRigidBodyDouble( btRigidBodyDoubleData* colObjData) -{ - btScalar mass = btScalar(colObjData->m_inverseMass? 1.f/colObjData->m_inverseMass : 0.f); - btVector3 localInertia; - localInertia.setZero(); - btCollisionShape** shapePtr = m_shapeMap.find(colObjData->m_collisionObjectData.m_collisionShape); - if (shapePtr && *shapePtr) - { - btTransform startTransform; - colObjData->m_collisionObjectData.m_worldTransform.m_origin.m_floats[3] = 0.f; - startTransform.deSerializeDouble(colObjData->m_collisionObjectData.m_worldTransform); - - // startTransform.setBasis(btMatrix3x3::getIdentity()); - btCollisionShape* shape = (btCollisionShape*)*shapePtr; - if (shape->isNonMoving()) - { - mass = 0.f; - } - if (mass) - { - shape->calculateLocalInertia(mass,localInertia); - } - bool isDynamic = mass!=0.f; - btRigidBody* body = createRigidBody(isDynamic,mass,startTransform,shape,colObjData->m_collisionObjectData.m_name); - body->setFriction(btScalar(colObjData->m_collisionObjectData.m_friction)); - body->setRestitution(btScalar(colObjData->m_collisionObjectData.m_restitution)); - btVector3 linearFactor,angularFactor; - linearFactor.deSerializeDouble(colObjData->m_linearFactor); - angularFactor.deSerializeDouble(colObjData->m_angularFactor); - body->setLinearFactor(linearFactor); - body->setAngularFactor(angularFactor); - - -#ifdef USE_INTERNAL_EDGE_UTILITY - if (shape->getShapeType() == TRIANGLE_MESH_SHAPE_PROXYTYPE) - { - btBvhTriangleMeshShape* trimesh = (btBvhTriangleMeshShape*)shape; - if (trimesh->getTriangleInfoMap()) - { - body->setCollisionFlags(body->getCollisionFlags() | btCollisionObject::CF_CUSTOM_MATERIAL_CALLBACK); - } - } -#endif //USE_INTERNAL_EDGE_UTILITY - m_bodyMap.insert(colObjData,body); - } else - { - printf("error: no shape found\n"); - } -} diff --git a/extern/bullet/src/Extras/Serialize/BulletWorldImporter/btWorldImporter.h b/extern/bullet/src/Extras/Serialize/BulletWorldImporter/btWorldImporter.h deleted file mode 100644 index 97c621fb583f..000000000000 --- a/extern/bullet/src/Extras/Serialize/BulletWorldImporter/btWorldImporter.h +++ /dev/null @@ -1,232 +0,0 @@ -/* -Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2012 Erwin Coumans http://bulletphysics.org - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - - -#ifndef BT_WORLD_IMPORTER_H -#define BT_WORLD_IMPORTER_H - -#include "LinearMath/btTransform.h" -#include "LinearMath/btVector3.h" -#include "LinearMath/btAlignedObjectArray.h" -#include "LinearMath/btHashMap.h" - -class btCollisionShape; -class btCollisionObject; -class btRigidBody; -class btTypedConstraint; -class btDynamicsWorld; -struct ConstraintInput; -class btRigidBodyColladaInfo; -struct btCollisionShapeData; -class btTriangleIndexVertexArray; -class btStridingMeshInterface; -struct btStridingMeshInterfaceData; -class btGImpactMeshShape; -class btOptimizedBvh; -struct btTriangleInfoMap; -class btBvhTriangleMeshShape; -class btPoint2PointConstraint; -class btHingeConstraint; -class btConeTwistConstraint; -class btGeneric6DofConstraint; -class btGeneric6DofSpringConstraint; -class btGeneric6DofSpring2Constraint; -class btSliderConstraint; -class btGearConstraint; -struct btContactSolverInfo; -struct btTypedConstraintData; -struct btTypedConstraintFloatData; -struct btTypedConstraintDoubleData; - -struct btRigidBodyDoubleData; -struct btRigidBodyFloatData; - -#ifdef BT_USE_DOUBLE_PRECISION -#define btRigidBodyData btRigidBodyDoubleData -#else -#define btRigidBodyData btRigidBodyFloatData -#endif//BT_USE_DOUBLE_PRECISION - -enum btWorldImporterFlags -{ - eRESTORE_EXISTING_OBJECTS=1,//don't create new objects -}; - -class btWorldImporter -{ -protected: - btDynamicsWorld* m_dynamicsWorld; - - int m_verboseMode; - int m_importerFlags; - - btAlignedObjectArray m_allocatedCollisionShapes; - btAlignedObjectArray m_allocatedRigidBodies; - btAlignedObjectArray m_allocatedConstraints; - btAlignedObjectArray m_allocatedBvhs; - btAlignedObjectArray m_allocatedTriangleInfoMaps; - btAlignedObjectArray m_allocatedTriangleIndexArrays; - btAlignedObjectArray m_allocatedbtStridingMeshInterfaceDatas; - - btAlignedObjectArray m_allocatedNames; - - btAlignedObjectArray m_indexArrays; - btAlignedObjectArray m_shortIndexArrays; - btAlignedObjectArray m_charIndexArrays; - - btAlignedObjectArray m_floatVertexArrays; - btAlignedObjectArray m_doubleVertexArrays; - - - btHashMap m_bvhMap; - btHashMap m_timMap; - - btHashMap m_nameShapeMap; - btHashMap m_nameBodyMap; - btHashMap m_nameConstraintMap; - btHashMap m_objectNameMap; - - btHashMap m_shapeMap; - btHashMap m_bodyMap; - - - //methods - - static btRigidBody& getFixedBody(); - - char* duplicateName(const char* name); - - btCollisionShape* convertCollisionShape( btCollisionShapeData* shapeData ); - - void convertConstraintBackwardsCompatible281(btTypedConstraintData* constraintData, btRigidBody* rbA, btRigidBody* rbB, int fileVersion); - void convertConstraintFloat(btTypedConstraintFloatData* constraintData, btRigidBody* rbA, btRigidBody* rbB, int fileVersion); - void convertConstraintDouble(btTypedConstraintDoubleData* constraintData, btRigidBody* rbA, btRigidBody* rbB, int fileVersion); - void convertRigidBodyFloat(btRigidBodyFloatData* colObjData); - void convertRigidBodyDouble( btRigidBodyDoubleData* colObjData); - -public: - - btWorldImporter(btDynamicsWorld* world); - - virtual ~btWorldImporter(); - - ///delete all memory collision shapes, rigid bodies, constraints etc. allocated during the load. - ///make sure you don't use the dynamics world containing objects after you call this method - virtual void deleteAllData(); - - void setVerboseMode(int verboseMode) - { - m_verboseMode = verboseMode; - } - - int getVerboseMode() const - { - return m_verboseMode; - } - - void setImporterFlags(int importerFlags) - { - m_importerFlags = importerFlags; - } - - int getImporterFlags() const - { - return m_importerFlags; - } - - - - // query for data - int getNumCollisionShapes() const; - btCollisionShape* getCollisionShapeByIndex(int index); - int getNumRigidBodies() const; - btCollisionObject* getRigidBodyByIndex(int index) const; - int getNumConstraints() const; - btTypedConstraint* getConstraintByIndex(int index) const; - int getNumBvhs() const; - btOptimizedBvh* getBvhByIndex(int index) const; - int getNumTriangleInfoMaps() const; - btTriangleInfoMap* getTriangleInfoMapByIndex(int index) const; - - // queris involving named objects - btCollisionShape* getCollisionShapeByName(const char* name); - btRigidBody* getRigidBodyByName(const char* name); - btTypedConstraint* getConstraintByName(const char* name); - const char* getNameForPointer(const void* ptr) const; - - ///those virtuals are called by load and can be overridden by the user - - virtual void setDynamicsWorldInfo(const btVector3& gravity, const btContactSolverInfo& solverInfo); - - //bodies - virtual btRigidBody* createRigidBody(bool isDynamic, btScalar mass, const btTransform& startTransform, btCollisionShape* shape,const char* bodyName); - virtual btCollisionObject* createCollisionObject( const btTransform& startTransform, btCollisionShape* shape,const char* bodyName); - - ///shapes - - virtual btCollisionShape* createPlaneShape(const btVector3& planeNormal,btScalar planeConstant); - virtual btCollisionShape* createBoxShape(const btVector3& halfExtents); - virtual btCollisionShape* createSphereShape(btScalar radius); - virtual btCollisionShape* createCapsuleShapeX(btScalar radius, btScalar height); - virtual btCollisionShape* createCapsuleShapeY(btScalar radius, btScalar height); - virtual btCollisionShape* createCapsuleShapeZ(btScalar radius, btScalar height); - - virtual btCollisionShape* createCylinderShapeX(btScalar radius,btScalar height); - virtual btCollisionShape* createCylinderShapeY(btScalar radius,btScalar height); - virtual btCollisionShape* createCylinderShapeZ(btScalar radius,btScalar height); - virtual btCollisionShape* createConeShapeX(btScalar radius,btScalar height); - virtual btCollisionShape* createConeShapeY(btScalar radius,btScalar height); - virtual btCollisionShape* createConeShapeZ(btScalar radius,btScalar height); - virtual class btTriangleIndexVertexArray* createTriangleMeshContainer(); - virtual btBvhTriangleMeshShape* createBvhTriangleMeshShape(btStridingMeshInterface* trimesh, btOptimizedBvh* bvh); - virtual btCollisionShape* createConvexTriangleMeshShape(btStridingMeshInterface* trimesh); - virtual btGImpactMeshShape* createGimpactShape(btStridingMeshInterface* trimesh); - virtual btStridingMeshInterfaceData* createStridingMeshInterfaceData(btStridingMeshInterfaceData* interfaceData); - - virtual class btConvexHullShape* createConvexHullShape(); - virtual class btCompoundShape* createCompoundShape(); - virtual class btScaledBvhTriangleMeshShape* createScaledTrangleMeshShape(btBvhTriangleMeshShape* meshShape,const btVector3& localScalingbtBvhTriangleMeshShape); - - virtual class btMultiSphereShape* createMultiSphereShape(const btVector3* positions,const btScalar* radi,int numSpheres); - - virtual btTriangleIndexVertexArray* createMeshInterface(btStridingMeshInterfaceData& meshData); - - ///acceleration and connectivity structures - virtual btOptimizedBvh* createOptimizedBvh(); - virtual btTriangleInfoMap* createTriangleInfoMap(); - - ///constraints - virtual btPoint2PointConstraint* createPoint2PointConstraint(btRigidBody& rbA,btRigidBody& rbB, const btVector3& pivotInA,const btVector3& pivotInB); - virtual btPoint2PointConstraint* createPoint2PointConstraint(btRigidBody& rbA,const btVector3& pivotInA); - virtual btHingeConstraint* createHingeConstraint(btRigidBody& rbA,btRigidBody& rbB, const btTransform& rbAFrame, const btTransform& rbBFrame, bool useReferenceFrameA=false); - virtual btHingeConstraint* createHingeConstraint(btRigidBody& rbA,const btTransform& rbAFrame, bool useReferenceFrameA=false); - virtual btConeTwistConstraint* createConeTwistConstraint(btRigidBody& rbA,btRigidBody& rbB,const btTransform& rbAFrame, const btTransform& rbBFrame); - virtual btConeTwistConstraint* createConeTwistConstraint(btRigidBody& rbA,const btTransform& rbAFrame); - virtual btGeneric6DofConstraint* createGeneric6DofConstraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& frameInA, const btTransform& frameInB ,bool useLinearReferenceFrameA); - virtual btGeneric6DofConstraint* createGeneric6DofConstraint(btRigidBody& rbB, const btTransform& frameInB, bool useLinearReferenceFrameB); - virtual btGeneric6DofSpringConstraint* createGeneric6DofSpringConstraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& frameInA, const btTransform& frameInB ,bool useLinearReferenceFrameA); - virtual btGeneric6DofSpring2Constraint* createGeneric6DofSpring2Constraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& frameInA, const btTransform& frameInB, int rotateOrder ); - - virtual btSliderConstraint* createSliderConstraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& frameInA, const btTransform& frameInB ,bool useLinearReferenceFrameA); - virtual btSliderConstraint* createSliderConstraint(btRigidBody& rbB, const btTransform& frameInB, bool useLinearReferenceFrameA); - virtual btGearConstraint* createGearConstraint(btRigidBody& rbA, btRigidBody& rbB, const btVector3& axisInA,const btVector3& axisInB, btScalar ratio); - - - - -}; - - -#endif //BT_WORLD_IMPORTER_H \ No newline at end of file diff --git a/extern/bullet/src/Extras/Serialize/BulletWorldImporter/premake4.lua b/extern/bullet/src/Extras/Serialize/BulletWorldImporter/premake4.lua deleted file mode 100644 index e7dbd9a77421..000000000000 --- a/extern/bullet/src/Extras/Serialize/BulletWorldImporter/premake4.lua +++ /dev/null @@ -1,17 +0,0 @@ - project "BulletWorldImporter" - - kind "StaticLib" - - includedirs { - "../BulletFileLoader", - "../../../src" - } - - if os.is("Linux") then - buildoptions{"-fPIC"} - end - - files { - "**.cpp", - "**.h" - } \ No newline at end of file diff --git a/extern/bullet/src/Extras/Serialize/BulletXmlWorldImporter/CMakeLists.txt b/extern/bullet/src/Extras/Serialize/BulletXmlWorldImporter/CMakeLists.txt deleted file mode 100644 index 9fd125e44514..000000000000 --- a/extern/bullet/src/Extras/Serialize/BulletXmlWorldImporter/CMakeLists.txt +++ /dev/null @@ -1,47 +0,0 @@ -INCLUDE_DIRECTORIES( - ${BULLET_PHYSICS_SOURCE_DIR}/src - ${BULLET_PHYSICS_SOURCE_DIR}/Extras/Serialize/BulletFileLoader - ${BULLET_PHYSICS_SOURCE_DIR}/Extras/Serialize/BulletWorldImporter - ${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/tinyxml2 -) - -ADD_LIBRARY( - BulletXmlWorldImporter - btBulletXmlWorldImporter.cpp - btBulletXmlWorldImporter.h - string_split.cpp - string_split.h - ${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/tinyxml2/tinyxml2.cpp -) - -SET_TARGET_PROPERTIES(BulletXmlWorldImporter PROPERTIES VERSION ${BULLET_VERSION}) -SET_TARGET_PROPERTIES(BulletXmlWorldImporter PROPERTIES SOVERSION ${BULLET_VERSION}) - -IF (BUILD_SHARED_LIBS) - TARGET_LINK_LIBRARIES(BulletXmlWorldImporter BulletWorldImporter BulletDynamics BulletCollision BulletFileLoader LinearMath) -ENDIF (BUILD_SHARED_LIBS) - -IF (INSTALL_EXTRA_LIBS) - IF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES) - #FILES_MATCHING requires CMake 2.6 - IF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5) - IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - INSTALL(TARGETS BulletXmlWorldImporter DESTINATION .) - ELSE (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - INSTALL(TARGETS BulletXmlWorldImporter - RUNTIME DESTINATION bin - LIBRARY DESTINATION lib${LIB_SUFFIX} - ARCHIVE DESTINATION lib${LIB_SUFFIX}) - - INSTALL(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} -DESTINATION ${INCLUDE_INSTALL_DIR} FILES_MATCHING PATTERN "*.h" PATTERN -".svn" EXCLUDE PATTERN "CMakeFiles" EXCLUDE) - ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - ENDIF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5) - - IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - SET_TARGET_PROPERTIES(BulletXmlWorldImporter PROPERTIES FRAMEWORK true) - SET_TARGET_PROPERTIES(BulletXmlWorldImporter PROPERTIES PUBLIC_HEADER "btBulletXmlWorldImporter.h") - ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) - ENDIF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES) -ENDIF (INSTALL_EXTRA_LIBS) diff --git a/extern/bullet/src/Extras/Serialize/BulletXmlWorldImporter/btBulletXmlWorldImporter.cpp b/extern/bullet/src/Extras/Serialize/BulletXmlWorldImporter/btBulletXmlWorldImporter.cpp deleted file mode 100644 index 51a6f5c23767..000000000000 --- a/extern/bullet/src/Extras/Serialize/BulletXmlWorldImporter/btBulletXmlWorldImporter.cpp +++ /dev/null @@ -1,903 +0,0 @@ -/* -Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2012 Erwin Coumans http://bulletphysics.org - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#include "btBulletXmlWorldImporter.h" -#include "tinyxml2.h" -#include "btBulletDynamicsCommon.h" -#include "string_split.h" -using namespace tinyxml2; - -struct MyLocalCaster -{ - void* m_ptr; - int m_int; - MyLocalCaster() - :m_ptr(0) - { - } -}; - - -btBulletXmlWorldImporter::btBulletXmlWorldImporter(btDynamicsWorld* world) - :btWorldImporter(world), - m_fileVersion(-1), - m_fileOk(false) -{ - -} - -btBulletXmlWorldImporter::~btBulletXmlWorldImporter() -{ - -} - -#if 0 -static int get_double_attribute_by_name(const XMLElement* pElement, const char* attribName,double* value) -{ - if ( !pElement ) - return 0; - - const XMLAttribute* pAttrib=pElement->FirstAttribute(); - while (pAttrib) - { - if (pAttrib->Name()==attribName) - if (pAttrib->QueryDoubleValue(value)==TIXML_SUCCESS) - return 1; - pAttrib=pAttrib->Next(); - } - return 0; -} -#endif - -static int get_int_attribute_by_name(const XMLElement* pElement, const char* attribName,int* value) -{ - if ( !pElement ) - return 0; - - const XMLAttribute* pAttrib=pElement->FirstAttribute(); - while (pAttrib) - { - if (!strcmp(pAttrib->Name(),attribName)) - if (pAttrib->QueryIntValue(value)==XML_SUCCESS) - return 1; -// if (pAttrib->QueryDoubleValue(&dval)==TIXML_SUCCESS) printf( " d=%1.1f", dval); - pAttrib=pAttrib->Next(); - } - return 0; -} - -void stringToFloatArray(const std::string& string, btAlignedObjectArray& floats) -{ - btAlignedObjectArray pieces; - - bullet_utils::split( pieces, string, " "); - for ( int i = 0; i < pieces.size(); ++i) - { - btAssert(pieces[i]!=""); - floats.push_back((float)atof(pieces[i].c_str())); - } - -} - -static btVector3FloatData TextToVector3Data(const char* txt) -{ - btAssert(txt); - btAlignedObjectArray floats; - stringToFloatArray(txt, floats); - btAssert(floats.size()==4); - - btVector3FloatData vec4; - vec4.m_floats[0] = floats[0]; - vec4.m_floats[1] = floats[1]; - vec4.m_floats[2] = floats[2]; - vec4.m_floats[3] = floats[3]; - return vec4; -} - -void btBulletXmlWorldImporter::deSerializeVector3FloatData(XMLNode* pParent,btAlignedObjectArray& vectors) -{ - XMLNode* flNode = pParent->FirstChildElement("m_floats"); - btAssert(flNode); - while (flNode && flNode->FirstChildElement()) - { - XMLText* pText = flNode->FirstChildElement()->ToText(); -// printf("value = %s\n",pText->Value()); - btVector3FloatData vec4 = TextToVector3Data(pText->Value()); - vectors.push_back(vec4); - flNode = flNode->NextSibling(); - } - -} - - -#define SET_INT_VALUE(xmlnode, targetdata, argname) \ - btAssert((xmlnode)->FirstChildElement(#argname) && (xmlnode)->FirstChildElement(#argname)->ToElement());\ - if ((xmlnode)->FirstChildElement(#argname) && (xmlnode)->FirstChildElement(#argname)->ToElement())\ - (targetdata)->argname= (int)atof(xmlnode->FirstChildElement(#argname)->ToElement()->GetText()); - - -#define SET_FLOAT_VALUE(xmlnode, targetdata, argname) \ - btAssert((xmlnode)->FirstChildElement(#argname) && (xmlnode)->FirstChildElement(#argname)->ToElement());\ - if ((xmlnode)->FirstChildElement(#argname) && (xmlnode)->FirstChildElement(#argname)->ToElement())\ - (targetdata)->argname= (float)atof(xmlnode->FirstChildElement(#argname)->ToElement()->GetText()); - - -#define SET_POINTER_VALUE(xmlnode, targetdata, argname, pointertype) \ - {\ - XMLNode* node = xmlnode->FirstChildElement(#argname);\ - btAssert(node);\ - if (node)\ - {\ - const char* txt = (node)->ToElement()->GetText();\ - MyLocalCaster cast;\ - cast.m_int = (int) atof(txt);\ - (targetdata).argname= (pointertype)cast.m_ptr;\ - }\ - } - -#define SET_VECTOR4_VALUE(xmlnode, targetdata, argname) \ - {\ - XMLNode* flNode = xmlnode->FirstChildElement(#argname);\ - btAssert(flNode);\ - if (flNode && flNode->FirstChildElement())\ - {\ - const char* txt= flNode->FirstChildElement()->ToElement()->GetText();\ - btVector3FloatData vec4 = TextToVector3Data(txt);\ - (targetdata)->argname.m_floats[0] = vec4.m_floats[0];\ - (targetdata)->argname.m_floats[1] = vec4.m_floats[1];\ - (targetdata)->argname.m_floats[2] = vec4.m_floats[2];\ - (targetdata)->argname.m_floats[3] = vec4.m_floats[3];\ - }\ - } - - -#define SET_MATRIX33_VALUE(n, targetdata, argname) \ -{\ - XMLNode* xmlnode = n->FirstChildElement(#argname);\ - btAssert(xmlnode);\ - if (xmlnode)\ - {\ - XMLNode* eleNode = xmlnode->FirstChildElement("m_el");\ - btAssert(eleNode);\ - if (eleNode&& eleNode->FirstChildElement())\ - {\ - const char* txt= eleNode->FirstChildElement()->ToElement()->GetText();\ - btVector3FloatData vec4 = TextToVector3Data(txt);\ - (targetdata)->argname.m_el[0].m_floats[0] = vec4.m_floats[0];\ - (targetdata)->argname.m_el[0].m_floats[1] = vec4.m_floats[1];\ - (targetdata)->argname.m_el[0].m_floats[2] = vec4.m_floats[2];\ - (targetdata)->argname.m_el[0].m_floats[3] = vec4.m_floats[3];\ - \ - XMLNode* n1 = eleNode->FirstChildElement()->NextSibling();\ - btAssert(n1);\ - if (n1)\ - {\ - const char* txt= n1->ToElement()->GetText();\ - btVector3FloatData vec4 = TextToVector3Data(txt);\ - (targetdata)->argname.m_el[1].m_floats[0] = vec4.m_floats[0];\ - (targetdata)->argname.m_el[1].m_floats[1] = vec4.m_floats[1];\ - (targetdata)->argname.m_el[1].m_floats[2] = vec4.m_floats[2];\ - (targetdata)->argname.m_el[1].m_floats[3] = vec4.m_floats[3];\ - \ - XMLNode* n2 = n1->NextSibling();\ - btAssert(n2);\ - if (n2)\ - {\ - const char* txt= n2->ToElement()->GetText();\ - btVector3FloatData vec4 = TextToVector3Data(txt);\ - (targetdata)->argname.m_el[2].m_floats[0] = vec4.m_floats[0];\ - (targetdata)->argname.m_el[2].m_floats[1] = vec4.m_floats[1];\ - (targetdata)->argname.m_el[2].m_floats[2] = vec4.m_floats[2];\ - (targetdata)->argname.m_el[2].m_floats[3] = vec4.m_floats[3];\ - }\ - }\ - }\ - }\ -}\ - -#define SET_TRANSFORM_VALUE(n, targetdata, argname) \ -{\ - XMLNode* trNode = n->FirstChildElement(#argname);\ - btAssert(trNode);\ - if (trNode)\ - {\ - SET_VECTOR4_VALUE(trNode,&(targetdata)->argname,m_origin)\ - SET_MATRIX33_VALUE(trNode, &(targetdata)->argname,m_basis)\ - }\ -}\ - - -void btBulletXmlWorldImporter::deSerializeCollisionShapeData(XMLNode* pParent, btCollisionShapeData* colShapeData) -{ - SET_INT_VALUE(pParent,colShapeData,m_shapeType) - colShapeData->m_name = 0; -} - - - -void btBulletXmlWorldImporter::deSerializeConvexHullShapeData(XMLNode* pParent) -{ - MyLocalCaster cast; - get_int_attribute_by_name(pParent->ToElement(),"pointer",&cast.m_int); - - btConvexHullShapeData* convexHullData = (btConvexHullShapeData*)btAlignedAlloc(sizeof(btConvexHullShapeData), 16); - - XMLNode* xmlConvexInt = pParent->FirstChildElement("m_convexInternalShapeData"); - btAssert(xmlConvexInt); - - XMLNode* xmlColShape = xmlConvexInt ->FirstChildElement("m_collisionShapeData"); - btAssert(xmlColShape); - - deSerializeCollisionShapeData(xmlColShape,&convexHullData->m_convexInternalShapeData.m_collisionShapeData); - - SET_FLOAT_VALUE(xmlConvexInt,&convexHullData->m_convexInternalShapeData,m_collisionMargin) - SET_VECTOR4_VALUE(xmlConvexInt,&convexHullData->m_convexInternalShapeData,m_localScaling) - SET_VECTOR4_VALUE(xmlConvexInt,&convexHullData->m_convexInternalShapeData,m_implicitShapeDimensions) - - //convexHullData->m_unscaledPointsFloatPtr - //#define SET_POINTER_VALUE(xmlnode, targetdata, argname, pointertype) - - { - XMLNode* node = pParent->FirstChildElement("m_unscaledPointsFloatPtr"); - btAssert(node); - if (node) - { - const char* txt = (node)->ToElement()->GetText(); - MyLocalCaster cast; - cast.m_int = (int) atof(txt); - (*convexHullData).m_unscaledPointsFloatPtr= (btVector3FloatData*) cast.m_ptr; - } - } - - SET_POINTER_VALUE(pParent,*convexHullData,m_unscaledPointsFloatPtr,btVector3FloatData*); - SET_POINTER_VALUE(pParent,*convexHullData,m_unscaledPointsDoublePtr,btVector3DoubleData*); - SET_INT_VALUE(pParent,convexHullData,m_numUnscaledPoints); - - m_collisionShapeData.push_back((btCollisionShapeData*)convexHullData); - m_pointerLookup.insert(cast.m_ptr,convexHullData); -} - -void btBulletXmlWorldImporter::deSerializeCompoundShapeChildData(XMLNode* pParent) -{ - MyLocalCaster cast; - get_int_attribute_by_name(pParent->ToElement(),"pointer",&cast.m_int); - - int numChildren = 0; - btAlignedObjectArray* compoundChildArrayPtr = new btAlignedObjectArray; - { - XMLNode* transNode = pParent->FirstChildElement("m_transform"); - XMLNode* colShapeNode = pParent->FirstChildElement("m_childShape"); - XMLNode* marginNode = pParent->FirstChildElement("m_childMargin"); - XMLNode* childTypeNode = pParent->FirstChildElement("m_childShapeType"); - - int i=0; - while (transNode && colShapeNode && marginNode && childTypeNode) - { - compoundChildArrayPtr->expandNonInitializing(); - SET_VECTOR4_VALUE (transNode,&compoundChildArrayPtr->at(i).m_transform,m_origin) - SET_MATRIX33_VALUE(transNode,&compoundChildArrayPtr->at(i).m_transform,m_basis) - - const char* txt = (colShapeNode)->ToElement()->GetText(); - MyLocalCaster cast; - cast.m_int = (int) atof(txt); - compoundChildArrayPtr->at(i).m_childShape = (btCollisionShapeData*) cast.m_ptr; - - btAssert(childTypeNode->ToElement()); - if (childTypeNode->ToElement()) - { - compoundChildArrayPtr->at(i).m_childShapeType = (int)atof(childTypeNode->ToElement()->GetText()); - } - - btAssert(marginNode->ToElement()); - if (marginNode->ToElement()) - { - compoundChildArrayPtr->at(i).m_childMargin = (float)atof(marginNode->ToElement()->GetText()); - } - - transNode = transNode->NextSiblingElement("m_transform"); - colShapeNode = colShapeNode->NextSiblingElement("m_childShape"); - marginNode = marginNode->NextSiblingElement("m_childMargin"); - childTypeNode = childTypeNode->NextSiblingElement("m_childShapeType"); - i++; - } - - numChildren = i; - - } - - btAssert(numChildren); - if (numChildren) - { - m_compoundShapeChildDataArrays.push_back(compoundChildArrayPtr); - btCompoundShapeChildData* cd = &compoundChildArrayPtr->at(0); - m_pointerLookup.insert(cast.m_ptr,cd); - } - -} - -void btBulletXmlWorldImporter::deSerializeCompoundShapeData(XMLNode* pParent) -{ - MyLocalCaster cast; - get_int_attribute_by_name(pParent->ToElement(),"pointer",&cast.m_int); - - btCompoundShapeData* compoundData = (btCompoundShapeData*) btAlignedAlloc(sizeof(btCompoundShapeData),16); - - XMLNode* xmlColShape = pParent ->FirstChildElement("m_collisionShapeData"); - btAssert(xmlColShape); - deSerializeCollisionShapeData(xmlColShape,&compoundData->m_collisionShapeData); - - SET_INT_VALUE(pParent, compoundData,m_numChildShapes); - - XMLNode* xmlShapeData = pParent->FirstChildElement("m_collisionShapeData"); - btAssert(xmlShapeData ); - - { - XMLNode* node = pParent->FirstChildElement("m_childShapePtr");\ - btAssert(node); - while (node) - { - const char* txt = (node)->ToElement()->GetText(); - MyLocalCaster cast; - cast.m_int = (int) atof(txt); - compoundData->m_childShapePtr = (btCompoundShapeChildData*) cast.m_ptr; - node = node->NextSiblingElement("m_childShapePtr"); - } - //SET_POINTER_VALUE(xmlColShape, *compoundData,m_childShapePtr,btCompoundShapeChildData*); - - } - SET_FLOAT_VALUE(pParent, compoundData,m_collisionMargin); - - m_collisionShapeData.push_back((btCollisionShapeData*)compoundData); - m_pointerLookup.insert(cast.m_ptr,compoundData); - -} - -void btBulletXmlWorldImporter::deSerializeStaticPlaneShapeData(XMLNode* pParent) -{ - MyLocalCaster cast; - get_int_attribute_by_name(pParent->ToElement(),"pointer",&cast.m_int); - - btStaticPlaneShapeData* planeData = (btStaticPlaneShapeData*) btAlignedAlloc(sizeof(btStaticPlaneShapeData),16); - - XMLNode* xmlShapeData = pParent->FirstChildElement("m_collisionShapeData"); - btAssert(xmlShapeData ); - deSerializeCollisionShapeData(xmlShapeData,&planeData->m_collisionShapeData); - - SET_VECTOR4_VALUE(pParent, planeData,m_localScaling); - SET_VECTOR4_VALUE(pParent, planeData,m_planeNormal); - SET_FLOAT_VALUE(pParent, planeData,m_planeConstant); - - m_collisionShapeData.push_back((btCollisionShapeData*)planeData); - m_pointerLookup.insert(cast.m_ptr,planeData); - -} - -void btBulletXmlWorldImporter::deSerializeDynamicsWorldData(XMLNode* pParent) -{ - btContactSolverInfo solverInfo; - //btVector3 gravity(0,0,0); - - //setDynamicsWorldInfo(gravity,solverInfo); - - //gravity and world info -} - -void btBulletXmlWorldImporter::deSerializeConvexInternalShapeData(XMLNode* pParent) -{ - MyLocalCaster cast; - get_int_attribute_by_name(pParent->ToElement(),"pointer",&cast.m_int); - - - btConvexInternalShapeData* convexShape = (btConvexInternalShapeData*) btAlignedAlloc(sizeof(btConvexInternalShapeData),16); - memset(convexShape,0,sizeof(btConvexInternalShapeData)); - - XMLNode* xmlShapeData = pParent->FirstChildElement("m_collisionShapeData"); - btAssert(xmlShapeData ); - - deSerializeCollisionShapeData(xmlShapeData,&convexShape->m_collisionShapeData); - - - SET_FLOAT_VALUE(pParent,convexShape,m_collisionMargin) - SET_VECTOR4_VALUE(pParent,convexShape,m_localScaling) - SET_VECTOR4_VALUE(pParent,convexShape,m_implicitShapeDimensions) - - m_collisionShapeData.push_back((btCollisionShapeData*)convexShape); - m_pointerLookup.insert(cast.m_ptr,convexShape); - -} - -/* -enum btTypedConstraintType -{ - POINT2POINT_CONSTRAINT_TYPE=3, - HINGE_CONSTRAINT_TYPE, - CONETWIST_CONSTRAINT_TYPE, -// D6_CONSTRAINT_TYPE, - SLIDER_CONSTRAINT_TYPE, - CONTACT_CONSTRAINT_TYPE, - D6_SPRING_CONSTRAINT_TYPE, - GEAR_CONSTRAINT_TYPE, - MAX_CONSTRAINT_TYPE -}; -*/ - - -void btBulletXmlWorldImporter::deSerializeGeneric6DofConstraintData(XMLNode* pParent) -{ - MyLocalCaster cast; - get_int_attribute_by_name(pParent->ToElement(),"pointer",&cast.m_int); - - btGeneric6DofConstraintData2* dof6Data = (btGeneric6DofConstraintData2*)btAlignedAlloc(sizeof(btGeneric6DofConstraintData2),16); - - - XMLNode* n = pParent->FirstChildElement("m_typeConstraintData"); - if (n) - { - SET_POINTER_VALUE(n,dof6Data->m_typeConstraintData,m_rbA,btRigidBodyData*); - SET_POINTER_VALUE(n,dof6Data->m_typeConstraintData,m_rbB,btRigidBodyData*); - dof6Data->m_typeConstraintData.m_name = 0;//tbd - SET_INT_VALUE(n,&dof6Data->m_typeConstraintData,m_objectType); - SET_INT_VALUE(n,&dof6Data->m_typeConstraintData,m_userConstraintType); - SET_INT_VALUE(n,&dof6Data->m_typeConstraintData,m_userConstraintId); - SET_INT_VALUE(n,&dof6Data->m_typeConstraintData,m_needsFeedback); - SET_FLOAT_VALUE(n,&dof6Data->m_typeConstraintData,m_appliedImpulse); - SET_FLOAT_VALUE(n,&dof6Data->m_typeConstraintData,m_dbgDrawSize); - SET_INT_VALUE(n,&dof6Data->m_typeConstraintData,m_disableCollisionsBetweenLinkedBodies); - SET_INT_VALUE(n,&dof6Data->m_typeConstraintData,m_overrideNumSolverIterations); - SET_FLOAT_VALUE(n,&dof6Data->m_typeConstraintData,m_breakingImpulseThreshold); - SET_INT_VALUE(n,&dof6Data->m_typeConstraintData,m_isEnabled); - - } - - SET_TRANSFORM_VALUE( pParent, dof6Data, m_rbAFrame); - SET_TRANSFORM_VALUE( pParent, dof6Data, m_rbBFrame); - SET_VECTOR4_VALUE(pParent, dof6Data, m_linearUpperLimit); - SET_VECTOR4_VALUE(pParent, dof6Data, m_linearLowerLimit); - SET_VECTOR4_VALUE(pParent, dof6Data, m_angularUpperLimit); - SET_VECTOR4_VALUE(pParent, dof6Data, m_angularLowerLimit); - SET_INT_VALUE(pParent, dof6Data,m_useLinearReferenceFrameA); - SET_INT_VALUE(pParent, dof6Data,m_useOffsetForConstraintFrame); - - m_constraintData.push_back((btTypedConstraintData2*)dof6Data); - m_pointerLookup.insert(cast.m_ptr,dof6Data); -} - -void btBulletXmlWorldImporter::deSerializeRigidBodyFloatData(XMLNode* pParent) -{ - MyLocalCaster cast; - - if (!get_int_attribute_by_name(pParent->ToElement(),"pointer",&cast.m_int)) - { - m_fileOk = false; - return; - } - - btRigidBodyData* rbData = (btRigidBodyData*)btAlignedAlloc(sizeof(btRigidBodyData),16); - - XMLNode* n = pParent->FirstChildElement("m_collisionObjectData"); - - if (n) - { - SET_POINTER_VALUE(n,rbData->m_collisionObjectData,m_collisionShape, void*); - SET_TRANSFORM_VALUE(n,&rbData->m_collisionObjectData,m_worldTransform); - SET_TRANSFORM_VALUE(n,&rbData->m_collisionObjectData,m_interpolationWorldTransform); - SET_VECTOR4_VALUE(n,&rbData->m_collisionObjectData,m_interpolationLinearVelocity) - SET_VECTOR4_VALUE(n,&rbData->m_collisionObjectData,m_interpolationAngularVelocity) - SET_VECTOR4_VALUE(n,&rbData->m_collisionObjectData,m_anisotropicFriction) - SET_FLOAT_VALUE(n,&rbData->m_collisionObjectData,m_contactProcessingThreshold); - SET_FLOAT_VALUE(n,&rbData->m_collisionObjectData,m_deactivationTime); - SET_FLOAT_VALUE(n,&rbData->m_collisionObjectData,m_friction); - SET_FLOAT_VALUE(n,&rbData->m_collisionObjectData,m_restitution); - SET_FLOAT_VALUE(n,&rbData->m_collisionObjectData,m_hitFraction); - SET_FLOAT_VALUE(n,&rbData->m_collisionObjectData,m_ccdSweptSphereRadius); - SET_FLOAT_VALUE(n,&rbData->m_collisionObjectData,m_ccdMotionThreshold); - SET_INT_VALUE(n,&rbData->m_collisionObjectData,m_hasAnisotropicFriction); - SET_INT_VALUE(n,&rbData->m_collisionObjectData,m_collisionFlags); - SET_INT_VALUE(n,&rbData->m_collisionObjectData,m_islandTag1); - SET_INT_VALUE(n,&rbData->m_collisionObjectData,m_companionId); - SET_INT_VALUE(n,&rbData->m_collisionObjectData,m_activationState1); - SET_INT_VALUE(n,&rbData->m_collisionObjectData,m_internalType); - SET_INT_VALUE(n,&rbData->m_collisionObjectData,m_checkCollideWith); - } - -// SET_VECTOR4_VALUE(pParent,rbData,m_linearVelocity); - - SET_MATRIX33_VALUE(pParent,rbData,m_invInertiaTensorWorld); - - - SET_VECTOR4_VALUE(pParent,rbData,m_linearVelocity) - SET_VECTOR4_VALUE(pParent,rbData,m_angularVelocity) - SET_VECTOR4_VALUE(pParent,rbData,m_angularFactor) - SET_VECTOR4_VALUE(pParent,rbData,m_linearFactor) - SET_VECTOR4_VALUE(pParent,rbData,m_gravity) - SET_VECTOR4_VALUE(pParent,rbData,m_gravity_acceleration ) - SET_VECTOR4_VALUE(pParent,rbData,m_invInertiaLocal) - SET_VECTOR4_VALUE(pParent,rbData,m_totalTorque) - SET_VECTOR4_VALUE(pParent,rbData,m_totalForce) - SET_FLOAT_VALUE(pParent,rbData,m_inverseMass); - SET_FLOAT_VALUE(pParent,rbData,m_linearDamping); - SET_FLOAT_VALUE(pParent,rbData,m_angularDamping); - SET_FLOAT_VALUE(pParent,rbData,m_additionalDampingFactor); - SET_FLOAT_VALUE(pParent,rbData,m_additionalLinearDampingThresholdSqr); - SET_FLOAT_VALUE(pParent,rbData,m_additionalAngularDampingThresholdSqr); - SET_FLOAT_VALUE(pParent,rbData,m_additionalAngularDampingFactor); - SET_FLOAT_VALUE(pParent,rbData,m_angularSleepingThreshold); - SET_FLOAT_VALUE(pParent,rbData,m_linearSleepingThreshold); - SET_INT_VALUE(pParent,rbData,m_additionalDamping); - - - m_rigidBodyData.push_back(rbData); - m_pointerLookup.insert(cast.m_ptr,rbData); - -// rbData->m_collisionObjectData.m_collisionShape = (void*) (int)atof(txt); -} - -/* - TETRAHEDRAL_SHAPE_PROXYTYPE, - CONVEX_TRIANGLEMESH_SHAPE_PROXYTYPE, - , - CONVEX_POINT_CLOUD_SHAPE_PROXYTYPE, - CUSTOM_POLYHEDRAL_SHAPE_TYPE, -//implicit convex shapes -IMPLICIT_CONVEX_SHAPES_START_HERE, - SPHERE_SHAPE_PROXYTYPE, - MULTI_SPHERE_SHAPE_PROXYTYPE, - CAPSULE_SHAPE_PROXYTYPE, - CONE_SHAPE_PROXYTYPE, - CONVEX_SHAPE_PROXYTYPE, - CYLINDER_SHAPE_PROXYTYPE, - UNIFORM_SCALING_SHAPE_PROXYTYPE, - MINKOWSKI_SUM_SHAPE_PROXYTYPE, - MINKOWSKI_DIFFERENCE_SHAPE_PROXYTYPE, - BOX_2D_SHAPE_PROXYTYPE, - CONVEX_2D_SHAPE_PROXYTYPE, - CUSTOM_CONVEX_SHAPE_TYPE, -//concave shapes -CONCAVE_SHAPES_START_HERE, - //keep all the convex shapetype below here, for the check IsConvexShape in broadphase proxy! - TRIANGLE_MESH_SHAPE_PROXYTYPE, - SCALED_TRIANGLE_MESH_SHAPE_PROXYTYPE, - ///used for demo integration FAST/Swift collision library and Bullet - FAST_CONCAVE_MESH_PROXYTYPE, - //terrain - TERRAIN_SHAPE_PROXYTYPE, -///Used for GIMPACT Trimesh integration - GIMPACT_SHAPE_PROXYTYPE, -///Multimaterial mesh - MULTIMATERIAL_TRIANGLE_MESH_PROXYTYPE, - - , - , - CUSTOM_CONCAVE_SHAPE_TYPE, -CONCAVE_SHAPES_END_HERE, - - , - - SOFTBODY_SHAPE_PROXYTYPE, - HFFLUID_SHAPE_PROXYTYPE, - HFFLUID_BUOYANT_CONVEX_SHAPE_PROXYTYPE, - INVALID_SHAPE_PROXYTYPE, - - MAX_BROADPHASE_COLLISION_TYPES -*/ - -void btBulletXmlWorldImporter::fixupConstraintData(btTypedConstraintData2* tcd) -{ - if (tcd->m_rbA) - { - btRigidBodyData** ptrptr = (btRigidBodyData**)m_pointerLookup.find(tcd->m_rbA); - btAssert(ptrptr); - tcd->m_rbA = ptrptr? *ptrptr : 0; - } - if (tcd->m_rbB) - { - btRigidBodyData** ptrptr = (btRigidBodyData**)m_pointerLookup.find(tcd->m_rbB); - btAssert(ptrptr); - tcd->m_rbB = ptrptr? *ptrptr : 0; - } - -} - -void btBulletXmlWorldImporter::fixupCollisionDataPointers(btCollisionShapeData* shapeData) -{ - - switch (shapeData->m_shapeType) - { - - case COMPOUND_SHAPE_PROXYTYPE: - { - btCompoundShapeData* compound = (btCompoundShapeData*) shapeData; - - void** cdptr = m_pointerLookup.find((void*)compound->m_childShapePtr); - btCompoundShapeChildData** c = (btCompoundShapeChildData**)cdptr; - btAssert(c); - if (c) - { - compound->m_childShapePtr = *c; - } else - { - compound->m_childShapePtr = 0; - } - break; - } - - case CONVEX_HULL_SHAPE_PROXYTYPE: - { - btConvexHullShapeData* convexData = (btConvexHullShapeData*)shapeData; - btVector3FloatData** ptrptr = (btVector3FloatData**)m_pointerLookup.find((void*)convexData->m_unscaledPointsFloatPtr); - btAssert(ptrptr); - if (ptrptr) - { - convexData->m_unscaledPointsFloatPtr = *ptrptr; - } else - { - convexData->m_unscaledPointsFloatPtr = 0; - } - break; - } - - case BOX_SHAPE_PROXYTYPE: - case TRIANGLE_SHAPE_PROXYTYPE: - case STATIC_PLANE_PROXYTYPE: - case EMPTY_SHAPE_PROXYTYPE: - break; - - default: - { - btAssert(0); - } - } -} - - -void btBulletXmlWorldImporter::auto_serialize_root_level_children(XMLNode* pParent) -{ - int numChildren = 0; - btAssert(pParent); - if (pParent) - { - XMLNode*pChild; - for ( pChild = pParent->FirstChildElement(); pChild != 0; pChild = pChild->NextSibling(), numChildren++) - { -// printf("child Name=%s\n", pChild->Value()); - if (!strcmp(pChild->Value(),"btVector3FloatData")) - { - MyLocalCaster cast; - get_int_attribute_by_name(pChild->ToElement(),"pointer",&cast.m_int); - - btAlignedObjectArray v; - deSerializeVector3FloatData(pChild,v); - int numVectors = v.size(); - btVector3FloatData* vectors= (btVector3FloatData*) btAlignedAlloc(sizeof(btVector3FloatData)*numVectors,16); - for (int i=0;iValue(),"btGeneric6DofConstraintData")) - { - deSerializeGeneric6DofConstraintData(pChild); - continue; - } - - if (!strcmp(pChild->Value(),"btStaticPlaneShapeData")) - { - deSerializeStaticPlaneShapeData(pChild); - continue; - } - - if (!strcmp(pChild->Value(),"btCompoundShapeData")) - { - deSerializeCompoundShapeData(pChild); - continue; - } - - if (!strcmp(pChild->Value(),"btCompoundShapeChildData")) - { - deSerializeCompoundShapeChildData(pChild); - continue; - } - - if (!strcmp(pChild->Value(),"btConvexHullShapeData")) - { - deSerializeConvexHullShapeData(pChild); - continue; - } - - if (!strcmp(pChild->Value(),"btDynamicsWorldFloatData")) - { - deSerializeDynamicsWorldData(pChild); - continue; - } - - - if (!strcmp(pChild->Value(),"btConvexInternalShapeData")) - { - deSerializeConvexInternalShapeData(pChild); - continue; - } - if (!strcmp(pChild->Value(),"btRigidBodyFloatData")) - { - deSerializeRigidBodyFloatData(pChild); - continue; - } - - //printf("Error: btBulletXmlWorldImporter doesn't support %s yet\n", pChild->Value()); - // btAssert(0); - } - } - - ///================================================================= - ///fixup pointers in various places, in the right order - - //fixup compoundshape child data - for (int i=0;i* childDataArray = m_compoundShapeChildDataArrays[i]; - for (int c=0;csize();c++) - { - btCompoundShapeChildData* childData = &childDataArray->at(c); - btCollisionShapeData** ptrptr = (btCollisionShapeData**)m_pointerLookup[childData->m_childShape]; - btAssert(ptrptr); - if (ptrptr) - { - childData->m_childShape = *ptrptr; - } - } - } - - for (int i=0;im_collisionShapeData.size();i++) - { - btCollisionShapeData* shapeData = m_collisionShapeData[i]; - fixupCollisionDataPointers(shapeData); - - } - - ///now fixup pointers - for (int i=0;im_collisionObjectData.m_collisionShape); - //btAssert(ptrptr); - rbData->m_collisionObjectData.m_broadphaseHandle = 0; - rbData->m_collisionObjectData.m_rootCollisionShape = 0; - rbData->m_collisionObjectData.m_name = 0;//tbd - if (ptrptr) - { - rbData->m_collisionObjectData.m_collisionShape = *ptrptr; - } - } - - - - for (int i=0;im_collisionShapeData.size();i++) - { - btCollisionShapeData* shapeData = m_collisionShapeData[i]; - btCollisionShape* shape = convertCollisionShape(shapeData); - if (shape) - { - m_shapeMap.insert(shapeData,shape); - } - if (shape&& shapeData->m_name) - { - char* newname = duplicateName(shapeData->m_name); - m_objectNameMap.insert(shape,newname); - m_nameShapeMap.insert(newname,shape); - } - } - - for (int i=0;im_rbA); - if (ptrptr) - { - rbA = btRigidBody::upcast(*ptrptr); - } - } - { - btCollisionObject** ptrptr = m_bodyMap.find(tcd->m_rbB); - if (ptrptr) - { - rbB = btRigidBody::upcast(*ptrptr); - } - } - if (rbA || rbB) - { - btAssert(0);//todo - //convertConstraint(tcd,rbA,rbB,isDoublePrecision, m_fileVersion); - } - - } -} - -void btBulletXmlWorldImporter::auto_serialize(XMLNode* pParent) -{ -// XMLElement* root = pParent->FirstChildElement("bullet_physics"); - if (pParent) - { - XMLNode*pChild; - for ( pChild = pParent->FirstChildElement(); pChild != 0; pChild = pChild->NextSibling()) - { - //if (pChild->Type()==XMLNode::TINYXML_ELEMENT) - { -// printf("root Name=%s\n", pChild->Value()); - auto_serialize_root_level_children(pChild); - } - } - } else - { - printf("ERROR: no bullet_physics element\n"); - } -} - - - - -bool btBulletXmlWorldImporter::loadFile(const char* fileName) -{ - XMLDocument doc; - - - XMLError loadOkay = doc.LoadFile(fileName); - - if (loadOkay==XML_SUCCESS) - { - if (get_int_attribute_by_name(doc.FirstChildElement()->ToElement(),"version", &m_fileVersion)) - { - if (m_fileVersion==281) - { - m_fileOk = true; - int itemcount; - get_int_attribute_by_name(doc.FirstChildElement()->ToElement(),"itemcount", &itemcount); - - auto_serialize(&doc); - return m_fileOk; - - } - } - } - return false; -} - - - - diff --git a/extern/bullet/src/Extras/Serialize/BulletXmlWorldImporter/btBulletXmlWorldImporter.h b/extern/bullet/src/Extras/Serialize/BulletXmlWorldImporter/btBulletXmlWorldImporter.h deleted file mode 100644 index aabf2576a899..000000000000 --- a/extern/bullet/src/Extras/Serialize/BulletXmlWorldImporter/btBulletXmlWorldImporter.h +++ /dev/null @@ -1,94 +0,0 @@ -/* -Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2012 Erwin Coumans http://bulletphysics.org - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#ifndef BT_BULLET_XML_WORLD_IMPORTER_H -#define BT_BULLET_XML_WORLD_IMPORTER_H - -#include "LinearMath/btScalar.h" - -class btDynamicsWorld; - -namespace tinyxml2 -{ - class XMLNode; -}; - -struct btConvexInternalShapeData; -struct btCollisionShapeData; -#ifdef BT_USE_DOUBLE_PRECISION -struct btRigidBodyDoubleData; -struct btTypedConstraintDoubleData; -#define btRigidBodyData btRigidBodyDoubleData -#define btTypedConstraintData2 btTypedConstraintDoubleData -#else -struct btRigidBodyFloatData; -struct btTypedConstraintFloatData; -#define btTypedConstraintData2 btTypedConstraintFloatData -#define btRigidBodyData btRigidBodyFloatData -#endif//BT_USE_DOUBLE_PRECISION - - -struct btCompoundShapeChildData; - -#include "LinearMath/btAlignedObjectArray.h" -#include "btWorldImporter.h" - - - -class btBulletXmlWorldImporter : public btWorldImporter -{ - -protected: - btAlignedObjectArray m_collisionShapeData; - btAlignedObjectArray* > m_compoundShapeChildDataArrays; - btAlignedObjectArray m_rigidBodyData; - btAlignedObjectArray m_constraintData; - btHashMap m_pointerLookup; - int m_fileVersion; - bool m_fileOk; - - void auto_serialize_root_level_children(tinyxml2::XMLNode* pParent); - void auto_serialize(tinyxml2::XMLNode* pParent); - - void deSerializeVector3FloatData(tinyxml2::XMLNode* pParent,btAlignedObjectArray& vectors); - - void fixupCollisionDataPointers(btCollisionShapeData* shapeData); - void fixupConstraintData(btTypedConstraintData2* tcd); - - //collision shapes data - void deSerializeCollisionShapeData(tinyxml2::XMLNode* pParent,btCollisionShapeData* colShapeData); - void deSerializeConvexInternalShapeData(tinyxml2::XMLNode* pParent); - void deSerializeStaticPlaneShapeData(tinyxml2::XMLNode* pParent); - void deSerializeCompoundShapeData(tinyxml2::XMLNode* pParent); - void deSerializeCompoundShapeChildData(tinyxml2::XMLNode* pParent); - void deSerializeConvexHullShapeData(tinyxml2::XMLNode* pParent); - void deSerializeDynamicsWorldData(tinyxml2::XMLNode* parent); - - ///bodies - void deSerializeRigidBodyFloatData(tinyxml2::XMLNode* pParent); - - ///constraints - void deSerializeGeneric6DofConstraintData(tinyxml2::XMLNode* pParent); - - public: - btBulletXmlWorldImporter(btDynamicsWorld* world); - - virtual ~btBulletXmlWorldImporter(); - - bool loadFile(const char* fileName); - -}; - -#endif //BT_BULLET_XML_WORLD_IMPORTER_H diff --git a/extern/bullet/src/Extras/Serialize/BulletXmlWorldImporter/premake4.lua b/extern/bullet/src/Extras/Serialize/BulletXmlWorldImporter/premake4.lua deleted file mode 100644 index dded9cff427d..000000000000 --- a/extern/bullet/src/Extras/Serialize/BulletXmlWorldImporter/premake4.lua +++ /dev/null @@ -1,16 +0,0 @@ - project "BulletXmlWorldImporter" - - kind "StaticLib" - --targetdir "../../lib" - includedirs { - "../BulletWorldImporter", - "../BulletFileLoader", - "../../../src", - "../../../examples/ThirdPartyLibs/tinyxml2" - } - - files { - "**.cpp", - "**.h", - "../../../examples/ThirdPartyLibs/tinyxml2/tinyxml2.cpp", - } diff --git a/extern/bullet/src/Extras/Serialize/BulletXmlWorldImporter/string_split.cpp b/extern/bullet/src/Extras/Serialize/BulletXmlWorldImporter/string_split.cpp deleted file mode 100644 index 424ded32a728..000000000000 --- a/extern/bullet/src/Extras/Serialize/BulletXmlWorldImporter/string_split.cpp +++ /dev/null @@ -1,250 +0,0 @@ -/* -Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2012 Erwin Coumans http://bulletphysics.org - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#include -//#include -#include -#include -#include - -#include "string_split.h" - -///todo: remove stl dependency - -namespace bullet_utils -{ - void split( btAlignedObjectArray&pieces, const std::string& vector_str, const std::string& separator) - { - char** strArray = str_split(vector_str.c_str(),separator.c_str()); - int numSubStr = str_array_len(strArray); - for (int i=0;i -#include "LinearMath/btAlignedObjectArray.h" - -#include - -namespace bullet_utils -{ - void split( btAlignedObjectArray&pieces, const std::string& vector_str, const std::string& separator); -}; - -///The string split C code is by Lars Wirzenius -///See http://stackoverflow.com/questions/2531605/how-to-split-a-string-with-a-delimiter-larger-than-one-single-char - - -/* Split a string into substrings. Return dynamic array of dynamically - allocated substrings, or NULL if there was an error. Caller is - expected to free the memory, for example with str_array_free. */ -char** str_split(const char* input, const char* sep); - -/* Free a dynamic array of dynamic strings. */ -void str_array_free(char** array); - -/* Return length of a NULL-delimited array of strings. */ -size_t str_array_len(char** array); - -#endif //STRING_SPLIT_H - diff --git a/extern/bullet/src/Extras/Serialize/CMakeLists.txt b/extern/bullet/src/Extras/Serialize/CMakeLists.txt deleted file mode 100644 index bc7ddde17053..000000000000 --- a/extern/bullet/src/Extras/Serialize/CMakeLists.txt +++ /dev/null @@ -1,20 +0,0 @@ - -IF (BUILD_BLEND_DEMO OR INTERNAL_UPDATE_SERIALIZATION_STRUCTURES) - #SUBDIRS(BlenderSerialize ) -ENDIF() - - -IF(INTERNAL_UPDATE_SERIALIZATION_STRUCTURES) - -# makesdna and HeaderGenerator are for advanced use only -# makesdna can re-generate the binary DNA representing the Bullet serialization structures -# Be very careful modifying any of this, otherwise the .bullet format becomes incompatible - - SUBDIRS ( BulletFileLoader BulletXmlWorldImporter BulletWorldImporter HeaderGenerator makesdna) - -ELSE(INTERNAL_UPDATE_SERIALIZATION_STRUCTURES) - - SUBDIRS ( BulletFileLoader BulletXmlWorldImporter BulletWorldImporter ) - -ENDIF (INTERNAL_UPDATE_SERIALIZATION_STRUCTURES) - diff --git a/extern/bullet/src/Extras/Serialize/HeaderGenerator/CMakeLists.txt b/extern/bullet/src/Extras/Serialize/HeaderGenerator/CMakeLists.txt deleted file mode 100644 index 3c1e862c8f70..000000000000 --- a/extern/bullet/src/Extras/Serialize/HeaderGenerator/CMakeLists.txt +++ /dev/null @@ -1,32 +0,0 @@ -############################################################################### -PROJECT(GEN) -FILE(GLOB cpp_SRC "*.cpp") -FILE(GLOB h_SRC "*.h") - - -SET(includes - . - ${BULLET_PHYSICS_SOURCE_DIR}/Extras/Serialize/BulletFileLoader - ${BULLET_PHYSICS_SOURCE_DIR}/Extras/Serialize/BlenderSerialize - ${BULLET_PHYSICS_SOURCE_DIR}/src -) - - -LINK_LIBRARIES( - BulletFileLoader LinearMath -) - -INCLUDE_DIRECTORIES(${includes}) - -SET(Main_LIBS LinearMath) - -ADD_EXECUTABLE(HeaderGenerator ${cpp_SRC} ${h_SRC}) - -IF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES) - ADD_CUSTOM_COMMAND( - TARGET HeaderGenerator - POST_BUILD - COMMAND ${CMAKE_COMMAND} ARGS -E copy_if_different ${BULLET_PHYSICS_SOURCE_DIR}/Extras/Serialize/HeaderGenerator/createDnaString.bat ${CMAKE_CURRENT_BINARY_DIR}/createDnaString.bat - COMMAND ${CMAKE_COMMAND} ARGS -E copy_if_different ${BULLET_PHYSICS_SOURCE_DIR}/Extras/Serialize/HeaderGenerator/bulletGenerate.py ${CMAKE_CURRENT_BINARY_DIR}/bulletGenerate.py - ) -ENDIF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES) diff --git a/extern/bullet/src/Extras/Serialize/HeaderGenerator/apiGen.cpp b/extern/bullet/src/Extras/Serialize/HeaderGenerator/apiGen.cpp deleted file mode 100644 index 2c4c763274a3..000000000000 --- a/extern/bullet/src/Extras/Serialize/HeaderGenerator/apiGen.cpp +++ /dev/null @@ -1,470 +0,0 @@ -/* Copyright (C) 2006 Charlie C -* -* This software is provided 'as-is', without any express or implied -* warranty. In no event will the authors be held liable for any damages -* arising from the use of this software. -* -* Permission is granted to anyone to use this software for any purpose, -* including commercial applications, and to alter it and redistribute it -* freely, subject to the following restrictions: -* -* 1. The origin of this software must not be misrepresented; you must not -* claim that you wrote the original software. If you use this software -* in a product, an acknowledgment in the product documentation would be -* appreciated but is not required. -* 2. Altered source versions must be plainly marked as such, and must not be -* misrepresented as being the original software. -* 3. This notice may not be removed or altered from any source distribution. -*/ -#include -#include "bDNA.h" -#include "bBlenderFile.h" -#include "btBulletFile.h" -#include "LinearMath/btSerializer.h" -#include "bCommon.h" -#include -#include -#include - -bool isBulletFile = true; - -using namespace bParse; -typedef std::string bString; - -/////////////////////////////////////////////////////////////////////////////// -typedef std::map bStringMap; -typedef std::vector bVariableList; -typedef std::vector bStringList; - - -/////////////////////////////////////////////////////////////////////////////// -static FILE *dump = 0; -static bDNA *mDNA =0; -static bStringMap mStructs; - - -/////////////////////////////////////////////////////////////////////////////// -class bVariable -{ -public: - bVariable(); - ~bVariable(); - - - bString dataType; - bString variableName; - - - bString functionName; - bString classCtor; - - bString memberVariable; - bString memberDataType; - bString functionArgs; - - - void initialize(bString dataType, bString variable, bStringMap refDataTable); - - bool isPtr; - bool isFunctionPtr; - bool isPtrToPtr; - bool isArray; - bool isCharArray; - bool isListBase; - bool isPadding; - bool isCommentedOut; - bool isGeneratedType; - bool isbString; -}; - -/////////////////////////////////////////////////////////////////////////////// -bool dataTypeStandard(bString dataType) -{ - if (dataType == "char") - return true; - if (dataType == "short") - return true; - if (dataType == "int") - return true; - if (dataType == "long") - return true; - if (dataType == "float") - return true; - if (dataType == "double") - return true; - if (dataType == "void") - return true; - if (dataType == "btScalar") - return true; - return false; -} - -/////////////////////////////////////////////////////////////////////////////// -void writeTemplate(short *structData) -{ - bString type = mDNA->getType(structData[0]); - bString className=type; - bString prefix = isBulletFile? "bullet_" : "blender_"; - - int thisLen = structData[1]; - structData+=2; - - bString fileName = prefix+type; - - bVariableList dataTypes; - bStringMap includeFiles; - - - for (int dataVal =0; dataValgetType(structData[0]); - bString dataName = mDNA->getName(structData[1]); - { - bString newDataType = ""; - bString newDataName = ""; - - bStringMap::iterator addB = mStructs.find(dataType); - if (addB != mStructs.end()) - { - newDataType = addB->second; - newDataName = dataName; - } - - else - { - if (dataTypeStandard(dataType)) - { - newDataType = dataType; - newDataName = dataName; - } - else - { - // Unresolved - // set it to an empty struct - // if it's not a ptr generate an error - newDataType = "bInvalidHandle"; - newDataName = dataName; - - if (dataName[0] != '*') - { - } - - } - } - - if (!newDataType.empty() && !newDataName.empty()) - { - bVariable var = bVariable(); - var.initialize(newDataType, newDataName, mStructs); - dataTypes.push_back(var); - } - } - - - bStringMap::iterator include = mStructs.find(dataType); - if (include != mStructs.end()) - { - if (dataName[0] != '*') - { - if (includeFiles.find(dataType)== includeFiles.end()) - { - includeFiles[dataType]=prefix+dataType; - } - } - } - } - - - fprintf(dump, "###############################################################\n"); - fprintf(dump, "%s = bStructClass()\n", fileName.c_str()); - fprintf(dump, "%s.name = '%s'\n", fileName.c_str(), className.c_str()); - fprintf(dump, "%s.filename = '%s'\n", fileName.c_str(), fileName.c_str()); - - bVariableList::iterator vars = dataTypes.begin(); - while (vars!= dataTypes.end()) - { - fprintf(dump, "%s.dataTypes.append('%s %s')\n", fileName.c_str(), vars->dataType.c_str(), vars->variableName.c_str()); - vars++; - } - - bStringMap::iterator inc = includeFiles.begin(); - while (inc != includeFiles.end()) - { - fprintf(dump, "%s.includes.append('%s.h')\n", fileName.c_str(), inc->second.c_str()); - inc++; - } - fprintf(dump, "DataTypeList.append(%s)\n", fileName.c_str()); -} - - -/////////////////////////////////////////////////////////////////////////////// -char data[]={ -"\n" -"class bStructClass:\n" -" def __init__(self):\n" -" self.name = \"\";\n" -" self.filename = \"\";\n" -" self.includes = []\n" -" self.dataTypes = []\n" -"\n\n" -"DataTypeList = []\n" -}; - - -/////////////////////////////////////////////////////////////////////////////// -int main(int argc,char** argv) -{ - using namespace bParse; - dump = fopen("dump.py", "w"); - - - if (!dump) return 0; - fprintf(dump, "%s\n", data); - - -#if 0 - char* filename = "../../../../data/r2d2_multibody.bullet"; - - if (argc==2) - filename = argv[1]; - - bString fileStr(filename); - bString extension(".bullet"); - - int index2 = fileStr.find(extension); - if (index2>=0) - isBulletFile=true; - - - FILE* fp = fopen (filename,"rb"); - - if (!fp) - { - printf("error: file not found %s\n",filename); - exit(0); - } - - char* memBuf = 0; - int len = 0; - - long currentpos = ftell(fp); /* save current cursor position */ - long newpos; - int bytesRead; - - fseek(fp, 0, SEEK_END); /* seek to end */ - newpos = ftell(fp); /* find position of end -- this is the length */ - fseek(fp, currentpos, SEEK_SET); /* restore previous cursor position */ - - len = newpos; - - memBuf = (char*)malloc(len); - bytesRead = fread(memBuf,len,1,fp); - - bool swap = false; - - - if (isBulletFile) - { - btBulletFile f(memBuf,len); - swap = (f.getFlags() & FD_ENDIAN_SWAP)!=0; - } else - { - bBlenderFile f(memBuf,len); - swap = (f.getFlags() & FD_ENDIAN_SWAP)!=0; - } -#else - isBulletFile = true; - bool swap = false; - char* memBuf = sBulletDNAstr; - int len = sBulletDNAlen; -#endif - - - char *blenderData = memBuf; - int sdnaPos=0; - int mDataStart = 12; - - char *tempBuffer = blenderData; - for (int i=0; iinitMemory(); - - mDNA->init(memBuf+sdnaPos, len-sdnaPos, swap); - - - for (int i=0; igetNumStructs(); i++) - { - short *structData = mDNA->getStruct(i); - bString type = mDNA->getType(structData[0]); - - bString className = type; - mStructs[type]=className; - } - - - for (int i=0; igetNumStructs(); i++) - { - short *structData = mDNA->getStruct(i); - writeTemplate(structData); - } - - delete mDNA; - fclose(dump); - return 0; -} -/////////////////////////////////////////////////////////////////////////////// - - -/////////////////////////////////////////////////////////////////////////////// -int _getArraySize(char* str) -{ - int a, mul=1; - char stri[100], *cp=0; - int len = (int)strlen(str); - - memcpy(stri, str, len+1); - for (a=0; a - -///work-in-progress -///This ReadBulletSample is kept as simple as possible without dependencies to the Bullet SDK. -///It can be used to load .bullet data for other physics SDKs -///For a more complete example how to load and convert Bullet data using the Bullet SDK check out -///the Bullet/Demos/SerializeDemo and Bullet/Serialize/BulletWorldImporter - -using namespace Bullet; - -enum LocalBroadphaseNativeTypes -{ - // polyhedral convex shapes - BOX_SHAPE_PROXYTYPE, - TRIANGLE_SHAPE_PROXYTYPE, - TETRAHEDRAL_SHAPE_PROXYTYPE, - CONVEX_TRIANGLEMESH_SHAPE_PROXYTYPE, - CONVEX_HULL_SHAPE_PROXYTYPE, - CONVEX_POINT_CLOUD_SHAPE_PROXYTYPE, - CUSTOM_POLYHEDRAL_SHAPE_TYPE, -//implicit convex shapes -IMPLICIT_CONVEX_SHAPES_START_HERE, - SPHERE_SHAPE_PROXYTYPE, - MULTI_SPHERE_SHAPE_PROXYTYPE, - CAPSULE_SHAPE_PROXYTYPE, - CONE_SHAPE_PROXYTYPE, - CONVEX_SHAPE_PROXYTYPE, - CYLINDER_SHAPE_PROXYTYPE, - UNIFORM_SCALING_SHAPE_PROXYTYPE, - MINKOWSKI_SUM_SHAPE_PROXYTYPE, - MINKOWSKI_DIFFERENCE_SHAPE_PROXYTYPE, - BOX_2D_SHAPE_PROXYTYPE, - CONVEX_2D_SHAPE_PROXYTYPE, - CUSTOM_CONVEX_SHAPE_TYPE, -//concave shapes -CONCAVE_SHAPES_START_HERE, - //keep all the convex shapetype below here, for the check IsConvexShape in broadphase proxy! - TRIANGLE_MESH_SHAPE_PROXYTYPE, - SCALED_TRIANGLE_MESH_SHAPE_PROXYTYPE, - ///used for demo integration FAST/Swift collision library and Bullet - FAST_CONCAVE_MESH_PROXYTYPE, - //terrain - TERRAIN_SHAPE_PROXYTYPE, -///Used for GIMPACT Trimesh integration - GIMPACT_SHAPE_PROXYTYPE, -///Multimaterial mesh - MULTIMATERIAL_TRIANGLE_MESH_PROXYTYPE, - - EMPTY_SHAPE_PROXYTYPE, - STATIC_PLANE_PROXYTYPE, - CUSTOM_CONCAVE_SHAPE_TYPE, -CONCAVE_SHAPES_END_HERE, - - COMPOUND_SHAPE_PROXYTYPE, - - SOFTBODY_SHAPE_PROXYTYPE, - HFFLUID_SHAPE_PROXYTYPE, - HFFLUID_BUOYANT_CONVEX_SHAPE_PROXYTYPE, - INVALID_SHAPE_PROXYTYPE, - - MAX_BROADPHASE_COLLISION_TYPES - -}; - -btBulletDataExtractor::btBulletDataExtractor() -{ -} - -btBulletDataExtractor::~btBulletDataExtractor() -{ -} - -void btBulletDataExtractor::convertAllObjects(bParse::btBulletFile* bulletFile2) -{ - int i; - - for (i=0;im_collisionShapes.size();i++) - { - btCollisionShapeData* shapeData = (btCollisionShapeData*)bulletFile2->m_collisionShapes[i]; - if (shapeData->m_name) - printf("converting shape %s\n", shapeData->m_name); - void* shape = convertCollisionShape(shapeData); - } - -} - - - -void* btBulletDataExtractor::convertCollisionShape( btCollisionShapeData* shapeData ) -{ - void* shape = 0; - - switch (shapeData->m_shapeType) - { - case STATIC_PLANE_PROXYTYPE: - { - btStaticPlaneShapeData* planeData = (btStaticPlaneShapeData*)shapeData; - void* shape = createPlaneShape(planeData->m_planeNormal,planeData->m_planeConstant, planeData->m_localScaling); - break; - } - - case CYLINDER_SHAPE_PROXYTYPE: - case CAPSULE_SHAPE_PROXYTYPE: - case BOX_SHAPE_PROXYTYPE: - case SPHERE_SHAPE_PROXYTYPE: - case MULTI_SPHERE_SHAPE_PROXYTYPE: - case CONVEX_HULL_SHAPE_PROXYTYPE: - { - btConvexInternalShapeData* bsd = (btConvexInternalShapeData*)shapeData; - - switch (shapeData->m_shapeType) - { - case BOX_SHAPE_PROXYTYPE: - { - shape = createBoxShape(bsd->m_implicitShapeDimensions, bsd->m_localScaling,bsd->m_collisionMargin); - break; - } - case SPHERE_SHAPE_PROXYTYPE: - { - shape = createSphereShape(bsd->m_implicitShapeDimensions.m_floats[0],bsd->m_localScaling, bsd->m_collisionMargin); - break; - } -#if 0 - case CAPSULE_SHAPE_PROXYTYPE: - { - btCapsuleShapeData* capData = (btCapsuleShapeData*)shapeData; - switch (capData->m_upAxis) - { - case 0: - { - shape = createCapsuleShapeX(implicitShapeDimensions.getY(),2*implicitShapeDimensions.getX()); - break; - } - case 1: - { - shape = createCapsuleShapeY(implicitShapeDimensions.getX(),2*implicitShapeDimensions.getY()); - break; - } - case 2: - { - shape = createCapsuleShapeZ(implicitShapeDimensions.getX(),2*implicitShapeDimensions.getZ()); - break; - } - default: - { - printf("error: wrong up axis for btCapsuleShape\n"); - } - - }; - - break; - } - case CYLINDER_SHAPE_PROXYTYPE: - { - btCylinderShapeData* cylData = (btCylinderShapeData*) shapeData; - btVector3 halfExtents = implicitShapeDimensions+margin; - switch (cylData->m_upAxis) - { - case 0: - { - shape = createCylinderShapeX(halfExtents.getY(),halfExtents.getX()); - break; - } - case 1: - { - shape = createCylinderShapeY(halfExtents.getX(),halfExtents.getY()); - break; - } - case 2: - { - shape = createCylinderShapeZ(halfExtents.getX(),halfExtents.getZ()); - break; - } - default: - { - printf("unknown Cylinder up axis\n"); - } - - }; - - - - break; - } - case MULTI_SPHERE_SHAPE_PROXYTYPE: - { - btMultiSphereShapeData* mss = (btMultiSphereShapeData*)bsd; - int numSpheres = mss->m_localPositionArraySize; - int i; - for ( i=0;im_localPositionArrayPtr[i].m_pos); - radii[i] = mss->m_localPositionArrayPtr[i].m_radius; - } - shape = new btMultiSphereShape(&tmpPos[0],&radii[0],numSpheres); - break; - } - case CONVEX_HULL_SHAPE_PROXYTYPE: - { - btConvexHullShapeData* convexData = (btConvexHullShapeData*)bsd; - int numPoints = convexData->m_numUnscaledPoints; - - btAlignedObjectArray tmpPoints; - tmpPoints.resize(numPoints); - int i; - for ( i=0;im_unscaledPointsFloatPtr) - tmpPoints[i].deSerialize(convexData->m_unscaledPointsFloatPtr[i]); - if (convexData->m_unscaledPointsDoublePtr) - tmpPoints[i].deSerializeDouble(convexData->m_unscaledPointsDoublePtr[i]); - } - shape = createConvexHullShape(); - - return shape; - break; - } -#endif - - default: - { - printf("error: cannot create shape type (%d)\n",shapeData->m_shapeType); - } - } - - break; - } -#if 0 - case TRIANGLE_MESH_SHAPE_PROXYTYPE: - { - btTriangleMeshShapeData* trimesh = (btTriangleMeshShapeData*)shapeData; - btTriangleIndexVertexArray* meshInterface = createMeshInterface(trimesh->m_meshInterface); - if (!meshInterface->getNumSubParts()) - { - return 0; - } - - btVector3 scaling; scaling.deSerializeFloat(trimesh->m_meshInterface.m_scaling); - meshInterface->setScaling(scaling); - - - btOptimizedBvh* bvh = 0; - - btBvhTriangleMeshShape* trimeshShape = createBvhTriangleMeshShape(meshInterface,bvh); - trimeshShape->setMargin(trimesh->m_collisionMargin); - shape = trimeshShape; - - if (trimesh->m_triangleInfoMap) - { - btTriangleInfoMap* map = createTriangleInfoMap(); - map->deSerialize(*trimesh->m_triangleInfoMap); - trimeshShape->setTriangleInfoMap(map); - -#ifdef USE_INTERNAL_EDGE_UTILITY - gContactAddedCallback = btAdjustInternalEdgeContactsCallback; -#endif //USE_INTERNAL_EDGE_UTILITY - - } - - //printf("trimesh->m_collisionMargin=%f\n",trimesh->m_collisionMargin); - break; - } - case COMPOUND_SHAPE_PROXYTYPE: - { - btCompoundShapeData* compoundData = (btCompoundShapeData*)shapeData; - btCompoundShape* compoundShape = createCompoundShape(); - - - btAlignedObjectArray childShapes; - for (int i=0;im_numChildShapes;i++) - { - btCollisionShape* childShape = convertCollisionShape(compoundData->m_childShapePtr[i].m_childShape); - if (childShape) - { - btTransform localTransform; - localTransform.deSerializeFloat(compoundData->m_childShapePtr[i].m_transform); - compoundShape->addChildShape(localTransform,childShape); - } else - { - printf("error: couldn't create childShape for compoundShape\n"); - } - - } - shape = compoundShape; - - break; - } - - case GIMPACT_SHAPE_PROXYTYPE: - { - btGImpactMeshShapeData* gimpactData = (btGImpactMeshShapeData*) shapeData; - if (gimpactData->m_gimpactSubType == CONST_GIMPACT_TRIMESH_SHAPE) - { - btTriangleIndexVertexArray* meshInterface = createMeshInterface(gimpactData->m_meshInterface); - btGImpactMeshShape* gimpactShape = createGimpactShape(meshInterface); - btVector3 localScaling; - localScaling.deSerializeFloat(gimpactData->m_localScaling); - gimpactShape->setLocalScaling(localScaling); - gimpactShape->setMargin(btScalar(gimpactData->m_collisionMargin)); - gimpactShape->updateBound(); - shape = gimpactShape; - } else - { - printf("unsupported gimpact sub type\n"); - } - break; - } - case SOFTBODY_SHAPE_PROXYTYPE: - { - return 0; - } -#endif - default: - { - printf("unsupported shape type (%d)\n",shapeData->m_shapeType); - } - } - - return shape; - -} - -void* btBulletDataExtractor::createBoxShape( const Bullet::btVector3FloatData& halfDimensions, const Bullet::btVector3FloatData& localScaling, float collisionMargin) -{ - printf("createBoxShape with halfDimensions %f,%f,%f\n",halfDimensions.m_floats[0], halfDimensions.m_floats[1],halfDimensions.m_floats[2]); - return 0; -} - -void* btBulletDataExtractor::createSphereShape( float radius, const Bullet::btVector3FloatData& localScaling, float collisionMargin) -{ - printf("createSphereShape with radius %f\n",radius); - return 0; -} - - -void* btBulletDataExtractor::createPlaneShape( const btVector3FloatData& planeNormal, float planeConstant, const Bullet::btVector3FloatData& localScaling) -{ - printf("createPlaneShape with normal %f,%f,%f and planeConstant\n",planeNormal.m_floats[0], planeNormal.m_floats[1],planeNormal.m_floats[2],planeConstant); - return 0; -} - diff --git a/extern/bullet/src/Extras/Serialize/ReadBulletSample/BulletDataExtractor.h b/extern/bullet/src/Extras/Serialize/ReadBulletSample/BulletDataExtractor.h deleted file mode 100644 index 8524716ba74f..000000000000 --- a/extern/bullet/src/Extras/Serialize/ReadBulletSample/BulletDataExtractor.h +++ /dev/null @@ -1,32 +0,0 @@ -#ifndef BULLET_DATA_EXTRACTOR_H -#define BULLET_DATA_EXTRACTOR_H - - -#include "../BulletFileLoader/autogenerated/bullet.h" - -namespace bParse -{ - class btBulletFile; -}; - -class btBulletDataExtractor -{ - public: - - btBulletDataExtractor(); - - virtual ~btBulletDataExtractor(); - - virtual void convertAllObjects(bParse::btBulletFile* bulletFile); - - virtual void* convertCollisionShape( Bullet::btCollisionShapeData* shapeData ); - - virtual void* createPlaneShape( const Bullet::btVector3FloatData& planeNormal, float planeConstant, const Bullet::btVector3FloatData& localScaling); - - virtual void* createBoxShape( const Bullet::btVector3FloatData& halfDimensions, const Bullet::btVector3FloatData& localScaling, float collisionMargin); - - virtual void* createSphereShape( float radius, const Bullet::btVector3FloatData& localScaling, float collisionMargin); - -}; - -#endif //BULLET_DATA_EXTRACTOR_H \ No newline at end of file diff --git a/extern/bullet/src/Extras/Serialize/ReadBulletSample/CMakeLists.txt b/extern/bullet/src/Extras/Serialize/ReadBulletSample/CMakeLists.txt deleted file mode 100644 index 6d6fbab588c5..000000000000 --- a/extern/bullet/src/Extras/Serialize/ReadBulletSample/CMakeLists.txt +++ /dev/null @@ -1,33 +0,0 @@ - -INCLUDE_DIRECTORIES( -${BULLET_PHYSICS_SOURCE_DIR}/src -) - -LINK_LIBRARIES( - BulletFileLoader -) -IF (WIN32) - SET(ADDITIONAL_SRC - ${BULLET_PHYSICS_SOURCE_DIR}/build/bullet.rc - ) -ENDIF() - -SET(READBULLET_SRC - main.cpp - BulletDataExtractor.cpp - BulletDataExtractor.h - ${BULLET_PHYSICS_SOURCE_DIR}/src/LinearMath/btSerializer.cpp - ${BULLET_PHYSICS_SOURCE_DIR}/src/LinearMath/btAlignedAllocator.cpp -) - -ADD_EXECUTABLE(AppReadBulletSample - ${READBULLET_SRC} - ${ADDITIONAL_SRC} -) - - -IF (INTERNAL_ADD_POSTFIX_EXECUTABLE_NAMES) - SET_TARGET_PROPERTIES(AppReadBulletSample PROPERTIES DEBUG_POSTFIX "_Debug") - SET_TARGET_PROPERTIES(AppReadBulletSample PROPERTIES MINSIZEREL_POSTFIX "_MinsizeRel") - SET_TARGET_PROPERTIES(AppReadBulletSample PROPERTIES RELWITHDEBINFO_POSTFIX "_RelWithDebugInfo") -ENDIF(INTERNAL_ADD_POSTFIX_EXECUTABLE_NAMES) diff --git a/extern/bullet/src/Extras/Serialize/ReadBulletSample/main.cpp b/extern/bullet/src/Extras/Serialize/ReadBulletSample/main.cpp deleted file mode 100644 index e9420c7d245c..000000000000 --- a/extern/bullet/src/Extras/Serialize/ReadBulletSample/main.cpp +++ /dev/null @@ -1,63 +0,0 @@ -/* -Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2011 Erwin Coumans http://continuousphysics.com/Bullet/ - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - - -#include -#include "../BulletFileLoader/btBulletFile.h" -#include "BulletDataExtractor.h" - -///This ReadBulletSample is kept as simple as possible without dependencies to the Bullet SDK. -///It can be used to load .bullet data for other physics SDKs -///For a more complete example how to load and convert Bullet data using the Bullet SDK check out -///the Bullet/Demos/SerializeDemo and Bullet/Serialize/BulletWorldImporter - -int main(int argc, char** argv) -{ - const char* fileName="testFile.bullet"; - bool verboseDumpAllTypes = false; - - bParse::btBulletFile* bulletFile2 = new bParse::btBulletFile(fileName); - - bool ok = (bulletFile2->getFlags()& bParse::FD_OK)!=0; - - if (ok) - bulletFile2->parse(verboseDumpAllTypes); - else - { - printf("Error loading file %s.\n",fileName); - exit(0); - } - ok = (bulletFile2->getFlags()& bParse::FD_OK)!=0; - if (!ok) - { - printf("Error parsing file %s.\n",fileName); - exit(0); - } - - if (verboseDumpAllTypes) - { - bulletFile2->dumpChunks(bulletFile2->getFileDNA()); - } - - - btBulletDataExtractor extractor; - - extractor.convertAllObjects(bulletFile2); - - delete bulletFile2; - - return 0; -} - diff --git a/extern/bullet/src/Extras/Serialize/makesdna/CMakeLists.txt b/extern/bullet/src/Extras/Serialize/makesdna/CMakeLists.txt deleted file mode 100644 index 3157b0ff417c..000000000000 --- a/extern/bullet/src/Extras/Serialize/makesdna/CMakeLists.txt +++ /dev/null @@ -1,51 +0,0 @@ -cmake_minimum_required(VERSION 2.4) - -IF(COMMAND cmake_policy) - cmake_policy(SET CMP0003 NEW) -ENDIF(COMMAND cmake_policy) - -INCLUDE_DIRECTORIES(${BULLET_PHYSICS_SOURCE_DIR}/src ) - -#FILE(GLOB INC_FILES ../*.h) - -SET (INC_FILES - DNA_rigidbody.h - - ${BULLET_PHYSICS_SOURCE_DIR}/src/LinearMath/btVector3.h - ${BULLET_PHYSICS_SOURCE_DIR}/src/LinearMath/btMatrix3x3.h - ${BULLET_PHYSICS_SOURCE_DIR}/src/LinearMath/btTransform.h - ${BULLET_PHYSICS_SOURCE_DIR}/src/BulletCollision/CollisionShapes/btCollisionShape.h - ${BULLET_PHYSICS_SOURCE_DIR}/src/BulletCollision/CollisionShapes/btConvexInternalShape.h - ${BULLET_PHYSICS_SOURCE_DIR}/src/BulletCollision/CollisionDispatch/btCollisionObject.h -) - -# Build makesdna executable -SET(SRC makesdna.cpp) -ADD_EXECUTABLE(makesdna ${SRC} ${INC_FILES}) - -IF (CMAKE_CL_64) - # Output BulletDNA.c - ADD_CUSTOM_COMMAND( - OUTPUT ${BULLET_PHYSICS_SOURCE_DIR}/src/LinearMath/btSerializer64.cpp - COMMAND ${CMAKE_CFG_INTDIR}/makesdna ${BULLET_PHYSICS_SOURCE_DIR}/src/LinearMath/btSerializer64.cpp ${BULLET_PHYSICS_SOURCE_DIR}/Extras/Serialize/CommonSerialize/ - DEPENDS makesdna - ) -SET(SRC ${BULLET_PHYSICS_SOURCE_DIR}/src/LinearMath/btSerializer64.cpp) - -ELSE() - # Output BulletDNA.c - ADD_CUSTOM_COMMAND( - OUTPUT ${BULLET_PHYSICS_SOURCE_DIR}/src/LinearMath/btSerializer.cpp - COMMAND ${CMAKE_CFG_INTDIR}/makesdna ${BULLET_PHYSICS_SOURCE_DIR}/src/LinearMath/btSerializer.cpp ${BULLET_PHYSICS_SOURCE_DIR}/Extras/Serialize/CommonSerialize/ - DEPENDS makesdna - ) -SET(SRC ${BULLET_PHYSICS_SOURCE_DIR}/src/LinearMath/btSerializer.cpp) - -ENDIF() - -# Build bf_dna library - - -ADD_LIBRARY(BulletDNA ${SRC} ${INC_FILES}) - -MESSAGE(STATUS "Configuring makesdna") diff --git a/extern/bullet/src/Extras/Serialize/makesdna/DNA_rigidbody.h b/extern/bullet/src/Extras/Serialize/makesdna/DNA_rigidbody.h deleted file mode 100644 index 010ed1bbfac4..000000000000 --- a/extern/bullet/src/Extras/Serialize/makesdna/DNA_rigidbody.h +++ /dev/null @@ -1,29 +0,0 @@ - -#ifndef DNA_RIGIDBODY_H -#define DNA_RIGIDBODY_H - - -struct PointerArray -{ - int m_size; - int m_capacity; - void *m_data; -}; - - -struct btPhysicsSystem -{ - PointerArray m_collisionShapes; - PointerArray m_collisionObjects; - PointerArray m_constraints; -}; - -///we need this to compute the pointer sizes -struct ListBase -{ - void *first; - void *last; -}; - - -#endif diff --git a/extern/bullet/src/Extras/Serialize/makesdna/makesdna.cpp b/extern/bullet/src/Extras/Serialize/makesdna/makesdna.cpp deleted file mode 100644 index 72795506e011..000000000000 --- a/extern/bullet/src/Extras/Serialize/makesdna/makesdna.cpp +++ /dev/null @@ -1,1263 +0,0 @@ -/// Current makesdna.cpp is a from Blender, but we will completely rewrite it in C++ under a ZLib license -/// The Original version is at https://svn.blender.org/svnroot/bf-blender/trunk/blender/source/blender/makesdna/intern/makesdna.c - -/** - * $Id$ - * - * ***** BEGIN GPL LICENSE BLOCK ***** - * - * This program is free software; you can redistribute it and/or - * modify it under the terms of the GNU General Public License - * as published by the Free Software Foundation; either version 2 - * of the License, or (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program; if not, write to the Free Software Foundation, - * Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. - * - * The Original Code is Copyright (C) 2001-2002 by NaN Holding BV. - * All rights reserved. - * - * The Original Code is: all of this file. - * - * Contributor(s): none yet. - * - * ***** END GPL LICENSE BLOCK ***** - * - * Struct muncher for making SDNA - * - * Originally by Ton, some mods by Frank, and some cleaning and - * extension by Nzc. - * - * Makesdna creates a .c file with a long string of numbers that - * encode the Blender file format. It is fast, because it is basically - * a binary dump. There are some details to mind when reconstructing - * the file (endianness and byte-alignment). - * - * This little program scans all structs that need to be serialized, - * and determined the names and types of all members. It calculates - * how much memory (on disk or in ram) is needed to store that struct, - * and the offsets for reaching a particular one. - * - * There is a facility to get verbose output from sdna. Search for - * debugSDNA. This int can be set to 0 (no output) to some int. Higher - * numbers give more output. - * */ - - -#ifdef __cplusplus -extern "C" { -#endif - -#if defined(_WIN32) && !defined(FREE_WINDOWS) - -/* The __intXX are built-in types of the visual complier! So we don't - * need to include anything else here. */ - -typedef signed __int8 int8_t; -typedef signed __int16 int16_t; -typedef signed __int32 int32_t; -typedef signed __int64 int64_t; - -typedef unsigned __int8 uint8_t; -typedef unsigned __int16 uint16_t; -typedef unsigned __int32 uint32_t; -typedef unsigned __int64 uint64_t; - -#ifndef _INTPTR_T_DEFINED - #ifdef _WIN64 - typedef __int64 btintptr_t; - #else - typedef long btintptr_t; - #endif - -#else - typedef intptr_t btintptr_t; -#endif - - - -#elif defined(__linux__) || defined(__NetBSD__) - - /* Linux-i386, Linux-Alpha, Linux-ppc */ -#include -typedef intptr_t btintptr_t; - -#elif defined (__APPLE__) - -#include -typedef intptr_t btintptr_t; - -#elif defined(FREE_WINDOWS) - -#include - -#else - - /* FreeBSD, Irix, Solaris */ -#include - -#endif /* ifdef platform for types */ - -#ifdef __cplusplus -} -#endif - - -#include -#include -#include - -//#include "DNA_sdna_types.h" -// include files for automatic dependancies -#include "DNA_rigidbody.h" -#include "LinearMath/btVector3.h" -#include "LinearMath/btQuaternion.h" -#include "LinearMath/btMatrix3x3.h" -#include "LinearMath/btTransform.h" -#include "BulletCollision/BroadphaseCollision/btQuantizedBvh.h" -#include "BulletCollision/CollisionShapes/btCollisionShape.h" -#include "BulletCollision/CollisionShapes/btStaticPlaneShape.h" -#include "BulletCollision/CollisionShapes/btConvexInternalShape.h" -#include "BulletCollision/CollisionShapes/btMultiSphereShape.h" -#include "BulletCollision/CollisionShapes/btConvexHullShape.h" -#include "BulletCollision/CollisionShapes/btStridingMeshInterface.h" -#include "BulletCollision/CollisionShapes/btBvhTriangleMeshShape.h" -#include "BulletCollision/CollisionShapes/btScaledBvhTriangleMeshShape.h" -#include "BulletCollision/CollisionShapes/btCompoundShape.h" -#include "BulletCollision/CollisionShapes/btCylinderShape.h" -#include "BulletCollision/CollisionShapes/btConeShape.h" -#include "BulletCollision/CollisionShapes/btCapsuleShape.h" -#include "BulletCollision/CollisionShapes/btTriangleInfoMap.h" -#include "BulletCollision/NarrowPhaseCollision/btPersistentManifold.h" -#include "BulletCollision/Gimpact/btGImpactShape.h" -#include "BulletCollision/CollisionDispatch/btCollisionObject.h" -#include "BulletDynamics/ConstraintSolver/btTypedConstraint.h" -#include "BulletDynamics/ConstraintSolver/btPoint2PointConstraint.h" -#include "BulletDynamics/ConstraintSolver/btHingeConstraint.h" -#include "BulletDynamics/ConstraintSolver/btConeTwistConstraint.h" -#include "BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.h" -#include "BulletDynamics/ConstraintSolver/btGeneric6DofSpringConstraint.h" -#include "BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.h" -#include "BulletDynamics/ConstraintSolver/btSliderConstraint.h" -#include "BulletDynamics/ConstraintSolver/btGearConstraint.h" -#include "BulletDynamics/ConstraintSolver/btContactSolverInfo.h" -#include "BulletDynamics/Dynamics/btDynamicsWorld.h" - -#include "BulletDynamics/Dynamics/btRigidBody.h" -#include "BulletSoftBody/btSoftBodyData.h" -#include "BulletDynamics/Featherstone/btMultiBody.h" -#include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h" - -#ifdef HAVE_CONFIG_H -#include -#endif - -#define SDNA_MAX_FILENAME_LENGTH 255 - -/* Included the path relative from /source/blender/ here, so we can move */ -/* headers around with more freedom. */ -char *includefiles[] = { - - // if you add files here, please add them at the end - // of makesdna.c (this file) as well - "../makesdna/DNA_rigidbody.h", - "../../../src/LinearMath/btVector3.h", - "../../../src/LinearMath/btQuaternion.h", - "../../../src/LinearMath/btMatrix3x3.h", - "../../../src/LinearMath/btTransform.h", - "../../../src/BulletCollision/BroadphaseCollision/btQuantizedBvh.h", - "../../../src/BulletCollision/CollisionShapes/btCollisionShape.h", - "../../../src/BulletCollision/CollisionShapes/btStaticPlaneShape.h", - "../../../src/BulletCollision/CollisionShapes/btConvexInternalShape.h", - "../../../src/BulletCollision/CollisionShapes/btMultiSphereShape.h", - "../../../src/BulletCollision/CollisionShapes/btStridingMeshInterface.h", - "../../../src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.h", - "../../../src/BulletCollision/CollisionShapes/btScaledBvhTriangleMeshShape.h", - "../../../src/BulletCollision/CollisionShapes/btCompoundShape.h", - "../../../src/BulletCollision/CollisionShapes/btCylinderShape.h", - "../../../src/BulletCollision/CollisionShapes/btConeShape.h", - "../../../src/BulletCollision/CollisionShapes/btCapsuleShape.h", - "../../../src/BulletCollision/CollisionShapes/btTriangleInfoMap.h", - "../../../src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.h", - "../../../src/BulletCollision/Gimpact/btGImpactShape.h", - "../../../src/BulletCollision/CollisionShapes/btConvexHullShape.h", - "../../../src/BulletCollision/CollisionDispatch/btCollisionObject.h", - "../../../src/BulletDynamics/ConstraintSolver/btContactSolverInfo.h", - "../../../src/BulletDynamics/Dynamics/btDynamicsWorld.h", - "../../../src/BulletDynamics/Dynamics/btRigidBody.h", - "../../../src/BulletDynamics/ConstraintSolver/btTypedConstraint.h", - "../../../src/BulletDynamics/ConstraintSolver/btPoint2PointConstraint.h", - "../../../src/BulletDynamics/ConstraintSolver/btHingeConstraint.h", - "../../../src/BulletDynamics/ConstraintSolver/btConeTwistConstraint.h", - "../../../src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.h", - "../../../src/BulletDynamics/ConstraintSolver/btGeneric6DofSpringConstraint.h", - "../../../src/BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.h", - "../../../src/BulletDynamics/ConstraintSolver/btSliderConstraint.h", - "../../../src/BulletDynamics/ConstraintSolver/btGearConstraint.h", - - "../../../src/BulletSoftBody/btSoftBodyData.h", - "../../../src/BulletDynamics/Featherstone/btMultiBody.h", - "../../../src/BulletDynamics/Featherstone/btMultiBodyLinkCollider.h", - // empty string to indicate end of includefiles - "" -}; - -void* malloc_and_setzero(int numbytes) -{ - char* buf = (char*)malloc(numbytes); - memset(buf,0,numbytes); - return buf; -} - -int maxdata= 500000, maxnr= 50000; -int nr_names=0; -int nr_types=0; -int nr_structs=0; -char **names, *namedata; /* at adress names[a] is string a */ -char **types, *typedata; /* at adress types[a] is string a */ -short *typelens; /* at typelens[a] is de length of type a */ -short *alphalens; /* contains sizes as they are calculated on the DEC Alpha (64 bits) */ -short **structs, *structdata; /* at sp= structs[a] is the first adress of a struct definition - sp[0] is type number - sp[1] is amount of elements - sp[2] sp[3] is typenr, namenr (etc) */ -/* - * debugSDNA: - * - 0 = no output, except errors - * - 1 = detail actions - * - 2 = full trace, tell which names and types were found - * - 4 = full trace, plus all gritty details - */ -int debugSDNA = 0; -int additional_slen_offset; - -/* ************************************************************************** */ -/* Functions */ -/* ************************************************************************** */ - -/** - * Add type to struct indexed by , if it was not yet found. - */ -int add_type(char *str, int len); - -/** - * Add variable to - */ -int add_name(char *str); - -/** - * Search whether this structure type was already found, and if not, - * add it. - */ -short *add_struct(int namecode); - -/** - * Remove comments from this buffer. Assumes that the buffer refers to - * ascii-code text. - */ -int preprocess_include(char *maindata, int len); - -/** - * Scan this file for serializable types. - */ -int convert_include(char *filename); - -/** - * Determine how many bytes are needed for an array. - */ -int arraysize(char *astr, int len); - -/** - * Determine how many bytes are needed for each struct. - */ -static int calculate_structlens(int); - -/** - * Construct the DNA.c file - */ -void dna_write(FILE *file, void *pntr, int size); - -/** - * Report all structures found so far, and print their lenghts. - */ -void printStructLenghts(void); - - - -/* ************************************************************************** */ -/* Implementation */ -/* ************************************************************************** */ - -/* ************************* MAKEN DNA ********************** */ - -int add_type(char *str, int len) -{ - int nr; - char *cp; - - if(str[0]==0) return -1; - - /* search through type array */ - for(nr=0; nr=maxnr) { - printf("too many types\n"); - return nr_types-1;; - } - nr_types++; - - return nr_types-1; -} - -/** - * - * Because of the weird way of tokenizing, we have to 'cast' function - * pointers to ... (*f)(), whatever the original signature. In fact, - * we add name and type at the same time... There are two special - * cases, unfortunately. These are explicitly checked. - * - * */ -int add_name(char *str) -{ - int nr, i, j, k; - char *cp; - char buf[255]; /* stupid limit, change it :) */ - char *name; - - additional_slen_offset = 0; - - if((str[0]==0) /* || (str[1]==0) */) return -1; - - if (str[0] == '(' && str[1] == '*') { - if (debugSDNA > 3) printf("\t\t\t\t*** Function pointer found\n"); - /* functionpointer: transform the type (sometimes) */ - i = 0; - j = 0; - - while (str[i] != ')') { - buf[i] = str[i]; - i++; - } - - /* Another number we need is the extra slen offset. This extra - * offset is the overshoot after a space. If there is no - * space, no overshoot should be calculated. */ - j = i; /* j at first closing brace */ - - if (debugSDNA > 3) printf("first brace after offset %d\n", i); - - j++; /* j beyond closing brace ? */ - while ((str[j] != 0) && (str[j] != ')' )) { - if (debugSDNA > 3) printf("seen %c ( %d) \n", str[j], str[j]); - j++; - } - if (debugSDNA > 3) printf("seen %c ( %d) \n", str[j], str[j]); - if (debugSDNA > 3) printf("special after offset %d\n", j); - - if (str[j] == 0 ) { - if (debugSDNA > 3) printf("offsetting for space\n"); - /* get additional offset */ - k = 0; - while (str[j] != ')') { - j++; - k++; - } - if (debugSDNA > 3) printf("extra offset %d\n", k); - additional_slen_offset = k; - } else if (str[j] == ')' ) { - if (debugSDNA > 3) printf("offsetting for brace\n"); - ; /* don't get extra offset */ - } else { - printf("Error during tokening function pointer argument list\n"); - } - - /* - * Put )(void) at the end? Maybe )(). Should check this with - * old sdna. Actually, sometimes )(), sometimes )(void...) - * Alas.. such is the nature of braindamage :( - * - * Sorted it out: always do )(), except for headdraw and - * windraw, part of ScrArea. This is important, because some - * linkers will treat different fp's differently when called - * !!! This has to do with interference in byte-alignment and - * the way args are pushed on the stack. - * - * */ - buf[i] = 0; - if (debugSDNA > 3) printf("Name before chomping: %s\n", buf); - if ( (strncmp(buf,"(*headdraw", 10) == 0) - || (strncmp(buf,"(*windraw", 9) == 0) ) { - buf[i] = ')'; - buf[i+1] = '('; - buf[i+2] = 'v'; - buf[i+3] = 'o'; - buf[i+4] = 'i'; - buf[i+5] = 'd'; - buf[i+6] = ')'; - buf[i+7] = 0; - } else { - buf[i] = ')'; - buf[i+1] = '('; - buf[i+2] = ')'; - buf[i+3] = 0; - } - /* now precede with buf*/ - if (debugSDNA > 3) printf("\t\t\t\t\tProposing fp name %s\n", buf); - name = buf; - } else { - /* normal field: old code */ - name = str; - } - - /* search name array */ - for(nr=0; nr=maxnr) { - printf("too many names\n"); - return nr_names-1; - } - nr_names++; - - return nr_names-1; -} - -short *add_struct(int namecode) -{ - int len; - short *sp; - - if(nr_structs==0) { - structs[0]= structdata; - } - else { - sp= structs[nr_structs-1]; - len= sp[1]; - structs[nr_structs]= sp+ 2*len+2; - } - - sp= structs[nr_structs]; - sp[0]= namecode; - - if(nr_structs>=maxnr) { - printf("too many structs\n"); - return sp; - } - nr_structs++; - - return sp; -} - -int preprocess_include(char *maindata, int len) -{ - int a, newlen, comment = 0; - char *cp, *temp, *md; - - temp= (char*) malloc_and_setzero(len); - memcpy(temp, maindata, len); - - // remove all c++ comments - /* replace all enters/tabs/etc with spaces */ - cp= temp; - a= len; - comment = 0; - while(a--) { - if(cp[0]=='/' && cp[1]=='/') { - comment = 1; - } else if (*cp<32) { - comment = 0; - } - if (comment || *cp<32 || *cp>128 ) *cp= 32; - cp++; - } - - - /* data from temp copy to maindata, remove comments and double spaces */ - cp= temp; - md= maindata; - newlen= 0; - comment= 0; - a= len; - while(a--) { - - if(cp[0]=='/' && cp[1]=='*') { - comment= 1; - cp[0]=cp[1]= 32; - } - if(cp[0]=='*' && cp[1]=='/') { - comment= 0; - cp[0]=cp[1]= 32; - } - - /* do not copy when: */ - if(comment); - else if( cp[0]==' ' && cp[1]==' ' ); - else if( cp[-1]=='*' && cp[0]==' ' ); /* pointers with a space */ - else { - md[0]= cp[0]; - md++; - newlen++; - } - cp++; - } - - free(temp); - return newlen; -} - -static void *read_file_data(char *filename, int *len_r) -{ -#ifdef WIN32 - FILE *fp= fopen(filename, "rb"); -#else - FILE *fp= fopen(filename, "r"); -#endif - void *data; - - if (!fp) { - *len_r= -1; - return NULL; - } - - fseek(fp, 0L, SEEK_END); - *len_r= ftell(fp); - fseek(fp, 0L, SEEK_SET); - - data= malloc_and_setzero(*len_r); - if (!data) { - *len_r= -1; - fclose(fp); - return NULL; - } - - if (fread(data, *len_r, 1, fp)!=1) { - *len_r= -1; - free(data); - fclose(fp); - return NULL; - } - - fclose(fp); - return data; -} - - -const char* skipStructTypes[]= -{ - "btContactSolverInfoData", - "btRigidBodyConstructionInfo", - "Euler", - "btConstraintInfo2", - "btConstraintSetting", - "btTriangleInfo", - "" -}; - -int skipStruct(const char* structType) -{ - int i=0; - while (strlen(skipStructTypes[i])) - { - if (strcmp(structType,skipStructTypes[i])==0) - { - return 1; - } - i++; - } - return 0; -} - -int convert_include(char *filename) -{ - /* read include file, skip structs with a '#' before it. - store all data in temporal arrays. - */ - int filelen, count, overslaan, slen, type, name, strct; - short *structpoin, *sp; - char *maindata, *mainend, *md, *md1; - - md= maindata= (char*)read_file_data(filename, &filelen); - if (filelen==-1) { - printf("Can't read file %s\n", filename); - return 1; - } - - filelen= preprocess_include(maindata, filelen); - mainend= maindata+filelen-1; - - /* we look for '{' and then back to 'struct' */ - count= 0; - overslaan= 0; - while(count 1) printf("\t|\t|-- detected struct %s\n", types[strct]); - - /* first lets make it all nice strings */ - md1= md+1; - while(*md1 != '}') { - if(md1>mainend) break; - - if(*md1==',' || *md1==' ') *md1= 0; - md1++; - } - - /* read types and names until first character that is not '}' */ - md1= md+1; - while( *md1 != '}' ) { - if(md1>mainend) break; - - /* skip when it says 'struct' or 'unsigned' or 'const' */ - if(*md1) { - if( strncmp(md1, "struct", 6)==0 ) md1+= 7; - if( strncmp(md1, "unsigned", 8)==0 ) md1+= 9; - if( strncmp(md1, "const", 5)==0 ) md1+= 6; - - /* we've got a type! */ - type= add_type(md1, 0); - - if (debugSDNA > 1) printf("\t|\t|\tfound type %s (", md1); - - md1+= strlen(md1); - - - /* read until ';' */ - while( *md1 != ';' ) { - if(md1>mainend) break; - - if(*md1) { - /* We've got a name. slen needs - * correction for function - * pointers! */ - slen= (int) strlen(md1); - if( md1[slen-1]==';' ) { - md1[slen-1]= 0; - - - name= add_name(md1); - slen += additional_slen_offset; - sp[0]= type; - sp[1]= name; - - if ((debugSDNA>1) && (names[name] != 0 )) printf("%s |", names[name]); - - structpoin[1]++; - sp+= 2; - - md1+= slen; - break; - } - - - name= add_name(md1); - slen += additional_slen_offset; - - sp[0]= type; - sp[1]= name; - if ((debugSDNA > 1) && (names[name] != 0 )) printf("%s ||", names[name]); - - structpoin[1]++; - sp+= 2; - - md1+= slen; - } - md1++; - } - - if (debugSDNA > 1) printf(")\n"); - - } - md1++; - } - } - } - } - } - count++; - md++; - } - - free(maindata); - - return 0; -} - -int arraysize(char *astr, int len) -{ - int a, mul=1; - char str[100], *cp=0; - - memcpy(str, astr, len+1); - - for(a=0; a= firststruct) { - if(sizeof(void *)==8 && (len % 8) ) { - printf("Align struct error: %s %s\n", types[structtype],cp); - dna_error = 1; - } - } - - /* 2-4 aligned/ */ - if(typelens[type]>3 && (len % 4) ) { - printf("Align 4 error in struct: %s %s (add %d padding bytes)\n", types[structtype], cp, len%4); - dna_error = 1; - } - else if(typelens[type]==2 && (len % 2) ) { - printf("Align 2 error in struct: %s %s (add %d padding bytes)\n", types[structtype], cp, len%2); - dna_error = 1; - } - - len += mul*typelens[type]; - alphalen += mul * alphalens[type]; - - } else { - len= 0; - alphalen = 0; - break; - } - } - - if (len==0) { - unknown++; - } else { - typelens[structtype]= len; - alphalens[structtype]= alphalen; - // two ways to detect if a struct contains a pointer: - // has_pointer is set or alphalen != len - if (has_pointer || alphalen != len) { - if (alphalen % 8) { - printf("alphalen = %d len = %d\n",alphalen,len); - printf("Sizeerror 8 in struct: %s (add %d bytes)\n", types[structtype], alphalen%8); - dna_error = 1; - } - } - - if(len % 4) { - printf("Sizeerror 4 in struct: %s (add %d bytes)\n", types[structtype], len%4); - dna_error = 1; - } - - } - } - } - - if(unknown==lastunknown) break; - } - - if(unknown) { - printf("ERROR: still %d structs unknown\n", unknown); - - if (debugSDNA) { - printf("*** Known structs : \n"); - - for(a=0; a= MAX_DNA_LINE_LENGTH) { - fprintf(file, "\n"); - linelength = 0; - } - } -} - -void printStructLenghts(void) -{ - int a, unknown= nr_structs, lastunknown, structtype; - short *structpoin; - printf("\n\n*** All detected structs:\n"); - - while(unknown) { - lastunknown= unknown; - unknown= 0; - - /* check all structs... */ - for(a=0; a -1) { - fflush(stdout); - printf("Running makesdna at debug level %d\n", debugSDNA); - - } - - /* the longest known struct is 50k, so we assume 100k is sufficent! */ - namedata= (char*)malloc_and_setzero(maxdata); - typedata= (char*)malloc_and_setzero(maxdata); - structdata= (short*)malloc_and_setzero(maxdata); - - /* a maximum of 5000 variables, must be sufficient? */ - names= (char**)malloc_and_setzero(sizeof(char *)*maxnr); - types= (char**)malloc_and_setzero(sizeof(char *)*maxnr); - typelens= (short*) malloc_and_setzero(sizeof(short)*maxnr); - alphalens= (short*)malloc_and_setzero(sizeof(short)*maxnr); - structs= (short**)malloc_and_setzero(sizeof(short)*maxnr); - - /* insertion of all known types */ - /* watch it: uint is not allowed! use in structs an unsigned int */ - add_type("char", 1); /* 0 */ - add_type("uchar", 1); /* 1 */ - add_type("short", 2); /* 2 */ - add_type("ushort", 2); /* 3 */ - add_type("int", 4); /* 4 */ - add_type("long", 4); /* 5 */ /* should it be 8 on 64 bits? */ - add_type("ulong", 4); /* 6 */ - add_type("float", 4); /* 7 */ - add_type("double", 8); /* 8 */ - add_type("void", 0); /* 9 */ - - // the defines above shouldn't be output in the padding file... - firststruct = nr_types; - - /* add all include files defined in the global array */ - /* Since the internal file+path name buffer has limited length, I do a */ - /* little test first... */ - /* Mind the breaking condition here! */ - if (debugSDNA) printf("\tStart of header scan:\n"); - for (i = 0; strlen(includefiles[i]); i++) { - sprintf(str, "%s%s", baseDirectory, includefiles[i]); - if (debugSDNA) printf("\t|-- Converting %s\n", str); - if (convert_include(str)) { - return (1); - } - } - if (debugSDNA) printf("\tFinished scanning %d headers.\n", i); - - if (calculate_structlens(firststruct)) { - // error - return(1); - } - - - /* FOR DEBUG */ - if (debugSDNA > 1) - { - int a,b; -/* short *elem; */ - short num_types; - - printf("nr_names %d nr_types %d nr_structs %d\n", nr_names, nr_types, nr_structs); - for(a=0; a -1) printf("Writing file ... "); - - if(nr_names==0 || nr_structs==0); - else { - strcpy(str, "SDNA"); - dna_write(file, str, 4); - - /* write names */ - strcpy(str, "NAME"); - dna_write(file, str, 4); - len= nr_names; - dna_write(file, &len, 4); - - /* calculate size of datablock with strings */ - cp= names[nr_names-1]; - cp+= strlen(names[nr_names-1]) + 1; /* +1: null-terminator */ - len= (btintptr_t) (cp - (char*) names[0]); - len= (len+3) & ~3; - dna_write(file, names[0], len); - - /* write TYPES */ - strcpy(str, "TYPE"); - dna_write(file, str, 4); - len= nr_types; - dna_write(file, &len, 4); - - /* calculate datablock size */ - cp= types[nr_types-1]; - cp+= strlen(types[nr_types-1]) + 1; /* +1: null-terminator */ - len= (btintptr_t) (cp - (char*) types[0]); - len= (len+3) & ~3; - - dna_write(file, types[0], len); - - /* WRITE TYPELENGTHS */ - strcpy(str, "TLEN"); - dna_write(file, str, 4); - - len= 2*nr_types; - if(nr_types & 1) len+= 2; - dna_write(file, typelens, len); - - /* WRITE STRUCTS */ - strcpy(str, "STRC"); - dna_write(file, str, 4); - len= nr_structs; - dna_write(file, &len, 4); - - /* calc datablock size */ - sp= structs[nr_structs-1]; - sp+= 2+ 2*( sp[1] ); - len= (btintptr_t) ((char*) sp - (char*) structs[0]); - len= (len+3) & ~3; - - dna_write(file, structs[0], len); - - /* a simple dna padding test */ - if (0) { - FILE *fp; - int a; - - fp= fopen("padding.c", "w"); - if(fp==NULL); - else { - - // add all include files defined in the global array - for (i = 0; strlen(includefiles[i]); i++) { - fprintf(fp, "#include \"%s%s\"\n", baseDirectory, includefiles[i]); - } - - fprintf(fp, "main(){\n"); - sp = typelens; - sp += firststruct; - for(a=firststruct; a -1) printf("done.\n"); - - return(0); -} - -/* ************************* END MAKE DNA ********************** */ - -static void make_bad_file(char *file) -{ - FILE *fp= fopen(file, "w"); - fprintf(fp, "ERROR! Cannot make correct DNA.c file, STUPID!\n"); - fclose(fp); -} - -#ifndef BASE_HEADER -#define BASE_HEADER "../" -#endif - -int main(int argc, char ** argv) -{ -// printf("btCollisionObject=%d\n",sizeof(btCollisionObject)); -// printf("btCollisionObjectData=%d\n",sizeof(btCollisionObjectData)); -// printf("btTransform=%d\n",sizeof(btTransform)); -// printf("btTransformData=%d\n",sizeof(btTransformData)); -// -// btCollisionObject* bla = new btCollisionObject(); -// btCollisionObjectData* bla2 = new btCollisionObjectData(); - - //int offsetof(bla,m_hasAnisotropicFriction); -/* - btTransformData m_worldTransform; - btTransform m_interpolationWorldTransform; - btVector3 m_interpolationLinearVelocity; - btVector3 m_interpolationAngularVelocity; - btVector3 m_anisotropicFriction; - bool m_hasAnisotropicFriction; - btScalar m_contactProcessingThreshold; - btBroadphaseProxy *m_broadphaseHandle; - btCollisionShape *m_collisionShape; - btCollisionShape *m_rootCollisionShape; - int m_collisionFlags; - int m_islandTag1; - int m_companionId; - int m_activationState1; - btScalar m_deactivationTime; - btScalar m_friction; - btScalar m_restitution; - void* m_userObjectPointer; - int m_internalType; - btScalar m_hitFraction; - btScalar m_ccdSweptSphereRadius; - btScalar m_ccdMotionThreshold; - bool m_checkCollideWith; - char m_pad[7]; -*/ - - FILE *file; - int return_status = 0; - - if (argc!=2 && argc!=3) { - printf("Usage: %s outfile.c [base directory]\n", argv[0]); - return_status = 1; - } else { - file = fopen(argv[1], "w"); - if (!file) { - printf ("Unable to open file: %s\n", argv[1]); - return_status = 1; - } else { - char baseDirectory[256]; - - if (argc==3) { - strcpy(baseDirectory, argv[2]); - } else { - strcpy(baseDirectory, BASE_HEADER); - } - - if (sizeof(void*)==8) - { - fprintf (file, "char sBulletDNAstr64[]= {\n"); - } else - { - fprintf (file, "char sBulletDNAstr[]= {\n"); - } - - if (make_structDNA(baseDirectory, file)) { - // error - fclose(file); - make_bad_file(argv[1]); - return_status = 1; - } else { - fprintf(file, "};\n"); - if (sizeof(void*)==8) - { - fprintf(file, "int sBulletDNAlen64= sizeof(sBulletDNAstr64);\n"); - } else - { - fprintf(file, "int sBulletDNAlen= sizeof(sBulletDNAstr);\n"); - } - - fclose(file); - } - } - } - - - return(return_status); -} - - -/* end of list */ diff --git a/extern/bullet/src/Extras/VHACD/inc/btAlignedAllocator.h b/extern/bullet/src/Extras/VHACD/inc/btAlignedAllocator.h deleted file mode 100644 index 4af0472af029..000000000000 --- a/extern/bullet/src/Extras/VHACD/inc/btAlignedAllocator.h +++ /dev/null @@ -1,104 +0,0 @@ -/* -Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#ifndef BT_ALIGNED_ALLOCATOR -#define BT_ALIGNED_ALLOCATOR - -///we probably replace this with our own aligned memory allocator -///so we replace _aligned_malloc and _aligned_free with our own -///that is better portable and more predictable - -#include "btScalar.h" -//#define BT_DEBUG_MEMORY_ALLOCATIONS 1 -#ifdef BT_DEBUG_MEMORY_ALLOCATIONS - -#define btAlignedAlloc(a, b) \ - btAlignedAllocInternal(a, b, __LINE__, __FILE__) - -#define btAlignedFree(ptr) \ - btAlignedFreeInternal(ptr, __LINE__, __FILE__) - -void* btAlignedAllocInternal(size_t size, int alignment, int line, char* filename); - -void btAlignedFreeInternal(void* ptr, int line, char* filename); - -#else -void* btAlignedAllocInternal(size_t size, int alignment); -void btAlignedFreeInternal(void* ptr); - -#define btAlignedAlloc(size, alignment) btAlignedAllocInternal(size, alignment) -#define btAlignedFree(ptr) btAlignedFreeInternal(ptr) - -#endif -typedef int size_type; - -typedef void*(btAlignedAllocFunc)(size_t size, int alignment); -typedef void(btAlignedFreeFunc)(void* memblock); -typedef void*(btAllocFunc)(size_t size); -typedef void(btFreeFunc)(void* memblock); - -///The developer can let all Bullet memory allocations go through a custom memory allocator, using btAlignedAllocSetCustom -void btAlignedAllocSetCustom(btAllocFunc* allocFunc, btFreeFunc* freeFunc); -///If the developer has already an custom aligned allocator, then btAlignedAllocSetCustomAligned can be used. The default aligned allocator pre-allocates extra memory using the non-aligned allocator, and instruments it. -void btAlignedAllocSetCustomAligned(btAlignedAllocFunc* allocFunc, btAlignedFreeFunc* freeFunc); - -///The btAlignedAllocator is a portable class for aligned memory allocations. -///Default implementations for unaligned and aligned allocations can be overridden by a custom allocator using btAlignedAllocSetCustom and btAlignedAllocSetCustomAligned. -template -class btAlignedAllocator { - - typedef btAlignedAllocator self_type; - -public: - //just going down a list: - btAlignedAllocator() {} - /* - btAlignedAllocator( const self_type & ) {} - */ - - template - btAlignedAllocator(const btAlignedAllocator&) {} - - typedef const T* const_pointer; - typedef const T& const_reference; - typedef T* pointer; - typedef T& reference; - typedef T value_type; - - pointer address(reference ref) const { return &ref; } - const_pointer address(const_reference ref) const { return &ref; } - pointer allocate(size_type n, const_pointer* hint = 0) - { - (void)hint; - return reinterpret_cast(btAlignedAlloc(sizeof(value_type) * n, Alignment)); - } - void construct(pointer ptr, const value_type& value) { new (ptr) value_type(value); } - void deallocate(pointer ptr) - { - btAlignedFree(reinterpret_cast(ptr)); - } - void destroy(pointer ptr) { ptr->~value_type(); } - - template - struct rebind { - typedef btAlignedAllocator other; - }; - template - self_type& operator=(const btAlignedAllocator&) { return *this; } - - friend bool operator==(const self_type&, const self_type&) { return true; } -}; - -#endif //BT_ALIGNED_ALLOCATOR diff --git a/extern/bullet/src/Extras/VHACD/inc/btAlignedObjectArray.h b/extern/bullet/src/Extras/VHACD/inc/btAlignedObjectArray.h deleted file mode 100644 index 49413c8566bc..000000000000 --- a/extern/bullet/src/Extras/VHACD/inc/btAlignedObjectArray.h +++ /dev/null @@ -1,448 +0,0 @@ -/* -Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#ifndef BT_OBJECT_ARRAY__ -#define BT_OBJECT_ARRAY__ - -#include "btAlignedAllocator.h" -#include "btScalar.h" // has definitions like SIMD_FORCE_INLINE - -///If the platform doesn't support placement new, you can disable BT_USE_PLACEMENT_NEW -///then the btAlignedObjectArray doesn't support objects with virtual methods, and non-trivial constructors/destructors -///You can enable BT_USE_MEMCPY, then swapping elements in the array will use memcpy instead of operator= -///see discussion here: http://continuousphysics.com/Bullet/phpBB2/viewtopic.php?t=1231 and -///http://www.continuousphysics.com/Bullet/phpBB2/viewtopic.php?t=1240 - -#define BT_USE_PLACEMENT_NEW 1 -//#define BT_USE_MEMCPY 1 //disable, because it is cumbersome to find out for each platform where memcpy is defined. It can be in or or otherwise... -#define BT_ALLOW_ARRAY_COPY_OPERATOR // enabling this can accidently perform deep copies of data if you are not careful - -#ifdef BT_USE_MEMCPY -#include -#include -#endif //BT_USE_MEMCPY - -#ifdef BT_USE_PLACEMENT_NEW -#include //for placement new -#endif //BT_USE_PLACEMENT_NEW - -///The btAlignedObjectArray template class uses a subset of the stl::vector interface for its methods -///It is developed to replace stl::vector to avoid portability issues, including STL alignment issues to add SIMD/SSE data -template -//template -class btAlignedObjectArray { - btAlignedAllocator m_allocator; - - int m_size; - int m_capacity; - T* m_data; - //PCK: added this line - bool m_ownsMemory; - -#ifdef BT_ALLOW_ARRAY_COPY_OPERATOR -public: - SIMD_FORCE_INLINE btAlignedObjectArray& operator=(const btAlignedObjectArray& other) - { - copyFromArray(other); - return *this; - } -#else //BT_ALLOW_ARRAY_COPY_OPERATOR -private: - SIMD_FORCE_INLINE btAlignedObjectArray& operator=(const btAlignedObjectArray& other); -#endif //BT_ALLOW_ARRAY_COPY_OPERATOR - -protected: - SIMD_FORCE_INLINE int allocSize(int size) - { - return (size ? size * 2 : 1); - } - SIMD_FORCE_INLINE void copy(int start, int end, T* dest) const - { - int i; - for (i = start; i < end; ++i) -#ifdef BT_USE_PLACEMENT_NEW - new (&dest[i]) T(m_data[i]); -#else - dest[i] = m_data[i]; -#endif //BT_USE_PLACEMENT_NEW - } - - SIMD_FORCE_INLINE void init() - { - //PCK: added this line - m_ownsMemory = true; - m_data = 0; - m_size = 0; - m_capacity = 0; - } - SIMD_FORCE_INLINE void destroy(int first, int last) - { - int i; - for (i = first; i < last; i++) { - m_data[i].~T(); - } - } - - SIMD_FORCE_INLINE void* allocate(int size) - { - if (size) - return m_allocator.allocate(size); - return 0; - } - - SIMD_FORCE_INLINE void deallocate() - { - if (m_data) { - //PCK: enclosed the deallocation in this block - if (m_ownsMemory) { - m_allocator.deallocate(m_data); - } - m_data = 0; - } - } - -public: - btAlignedObjectArray() - { - init(); - } - - ~btAlignedObjectArray() - { - clear(); - } - - ///Generally it is best to avoid using the copy constructor of an btAlignedObjectArray, and use a (const) reference to the array instead. - btAlignedObjectArray(const btAlignedObjectArray& otherArray) - { - init(); - - int otherSize = otherArray.size(); - resize(otherSize); - otherArray.copy(0, otherSize, m_data); - } - - /// return the number of elements in the array - SIMD_FORCE_INLINE int size() const - { - return m_size; - } - - SIMD_FORCE_INLINE const T& at(int n) const - { - btAssert(n >= 0); - btAssert(n < size()); - return m_data[n]; - } - - SIMD_FORCE_INLINE T& at(int n) - { - btAssert(n >= 0); - btAssert(n < size()); - return m_data[n]; - } - - SIMD_FORCE_INLINE const T& operator[](int n) const - { - btAssert(n >= 0); - btAssert(n < size()); - return m_data[n]; - } - - SIMD_FORCE_INLINE T& operator[](int n) - { - btAssert(n >= 0); - btAssert(n < size()); - return m_data[n]; - } - - ///clear the array, deallocated memory. Generally it is better to use array.resize(0), to reduce performance overhead of run-time memory (de)allocations. - SIMD_FORCE_INLINE void clear() - { - destroy(0, size()); - - deallocate(); - - init(); - } - - SIMD_FORCE_INLINE void pop_back() - { - btAssert(m_size > 0); - m_size--; - m_data[m_size].~T(); - } - - ///resize changes the number of elements in the array. If the new size is larger, the new elements will be constructed using the optional second argument. - ///when the new number of elements is smaller, the destructor will be called, but memory will not be freed, to reduce performance overhead of run-time memory (de)allocations. - SIMD_FORCE_INLINE void resize(int newsize, const T& fillData = T()) - { - int curSize = size(); - - if (newsize < curSize) { - for (int i = newsize; i < curSize; i++) { - m_data[i].~T(); - } - } - else { - if (newsize > size()) { - reserve(newsize); - } -#ifdef BT_USE_PLACEMENT_NEW - for (int i = curSize; i < newsize; i++) { - new (&m_data[i]) T(fillData); - } -#endif //BT_USE_PLACEMENT_NEW - } - - m_size = newsize; - } - - SIMD_FORCE_INLINE T& expandNonInitializing() - { - int sz = size(); - if (sz == capacity()) { - reserve(allocSize(size())); - } - m_size++; - - return m_data[sz]; - } - - SIMD_FORCE_INLINE T& expand(const T& fillValue = T()) - { - int sz = size(); - if (sz == capacity()) { - reserve(allocSize(size())); - } - m_size++; -#ifdef BT_USE_PLACEMENT_NEW - new (&m_data[sz]) T(fillValue); //use the in-place new (not really allocating heap memory) -#endif - - return m_data[sz]; - } - - SIMD_FORCE_INLINE void push_back(const T& _Val) - { - int sz = size(); - if (sz == capacity()) { - reserve(allocSize(size())); - } - -#ifdef BT_USE_PLACEMENT_NEW - new (&m_data[m_size]) T(_Val); -#else - m_data[size()] = _Val; -#endif //BT_USE_PLACEMENT_NEW - - m_size++; - } - - /// return the pre-allocated (reserved) elements, this is at least as large as the total number of elements,see size() and reserve() - SIMD_FORCE_INLINE int capacity() const - { - return m_capacity; - } - - SIMD_FORCE_INLINE void reserve(int _Count) - { // determine new minimum length of allocated storage - if (capacity() < _Count) { // not enough room, reallocate - T* s = (T*)allocate(_Count); - - copy(0, size(), s); - - destroy(0, size()); - - deallocate(); - - //PCK: added this line - m_ownsMemory = true; - - m_data = s; - - m_capacity = _Count; - } - } - - class less { - public: - bool operator()(const T& a, const T& b) - { - return (a < b); - } - }; - - template - void quickSortInternal(const L& CompareFunc, int lo, int hi) - { - // lo is the lower index, hi is the upper index - // of the region of array a that is to be sorted - int i = lo, j = hi; - T x = m_data[(lo + hi) / 2]; - - // partition - do { - while (CompareFunc(m_data[i], x)) - i++; - while (CompareFunc(x, m_data[j])) - j--; - if (i <= j) { - swap(i, j); - i++; - j--; - } - } while (i <= j); - - // recursion - if (lo < j) - quickSortInternal(CompareFunc, lo, j); - if (i < hi) - quickSortInternal(CompareFunc, i, hi); - } - - template - void quickSort(const L& CompareFunc) - { - //don't sort 0 or 1 elements - if (size() > 1) { - quickSortInternal(CompareFunc, 0, size() - 1); - } - } - - ///heap sort from http://www.csse.monash.edu.au/~lloyd/tildeAlgDS/Sort/Heap/ - template - void downHeap(T* pArr, int k, int n, const L& CompareFunc) - { - /* PRE: a[k+1..N] is a heap */ - /* POST: a[k..N] is a heap */ - - T temp = pArr[k - 1]; - /* k has child(s) */ - while (k <= n / 2) { - int child = 2 * k; - - if ((child < n) && CompareFunc(pArr[child - 1], pArr[child])) { - child++; - } - /* pick larger child */ - if (CompareFunc(temp, pArr[child - 1])) { - /* move child up */ - pArr[k - 1] = pArr[child - 1]; - k = child; - } - else { - break; - } - } - pArr[k - 1] = temp; - } /*downHeap*/ - - void swap(int index0, int index1) - { -#ifdef BT_USE_MEMCPY - char temp[sizeof(T)]; - memcpy(temp, &m_data[index0], sizeof(T)); - memcpy(&m_data[index0], &m_data[index1], sizeof(T)); - memcpy(&m_data[index1], temp, sizeof(T)); -#else - T temp = m_data[index0]; - m_data[index0] = m_data[index1]; - m_data[index1] = temp; -#endif //BT_USE_PLACEMENT_NEW - } - - template - void heapSort(const L& CompareFunc) - { - /* sort a[0..N-1], N.B. 0 to N-1 */ - int k; - int n = m_size; - for (k = n / 2; k > 0; k--) { - downHeap(m_data, k, n, CompareFunc); - } - - /* a[1..N] is now a heap */ - while (n >= 1) { - swap(0, n - 1); /* largest of a[0..n-1] */ - - n = n - 1; - /* restore a[1..i-1] heap */ - downHeap(m_data, 1, n, CompareFunc); - } - } - - ///non-recursive binary search, assumes sorted array - int findBinarySearch(const T& key) const - { - int first = 0; - int last = size() - 1; - - //assume sorted array - while (first <= last) { - int mid = (first + last) / 2; // compute mid point. - if (key > m_data[mid]) - first = mid + 1; // repeat search in top half. - else if (key < m_data[mid]) - last = mid - 1; // repeat search in bottom half. - else - return mid; // found it. return position ///// - } - return size(); // failed to find key - } - - int findLinearSearch(const T& key) const - { - int index = size(); - int i; - - for (i = 0; i < size(); i++) { - if (m_data[i] == key) { - index = i; - break; - } - } - return index; - } - - void remove(const T& key) - { - - int findIndex = findLinearSearch(key); - if (findIndex < size()) { - swap(findIndex, size() - 1); - pop_back(); - } - } - - //PCK: whole function - void initializeFromBuffer(void* buffer, int size, int capacity) - { - clear(); - m_ownsMemory = false; - m_data = (T*)buffer; - m_size = size; - m_capacity = capacity; - } - - void copyFromArray(const btAlignedObjectArray& otherArray) - { - int otherSize = otherArray.size(); - resize(otherSize); - otherArray.copy(0, otherSize, m_data); - } -}; - -#endif //BT_OBJECT_ARRAY__ diff --git a/extern/bullet/src/Extras/VHACD/inc/btConvexHullComputer.h b/extern/bullet/src/Extras/VHACD/inc/btConvexHullComputer.h deleted file mode 100644 index d59b81e5d58d..000000000000 --- a/extern/bullet/src/Extras/VHACD/inc/btConvexHullComputer.h +++ /dev/null @@ -1,97 +0,0 @@ -/* -Copyright (c) 2011 Ole Kniemeyer, MAXON, www.maxon.net - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#ifndef BT_CONVEX_HULL_COMPUTER_H -#define BT_CONVEX_HULL_COMPUTER_H - -#include "btAlignedObjectArray.h" -#include "btVector3.h" - -/// Convex hull implementation based on Preparata and Hong -/// See http://code.google.com/p/bullet/issues/detail?id=275 -/// Ole Kniemeyer, MAXON Computer GmbH -class btConvexHullComputer { -private: - btScalar compute(const void* coords, bool doubleCoords, int stride, int count, btScalar shrink, btScalar shrinkClamp); - -public: - class Edge { - private: - int next; - int reverse; - int targetVertex; - - friend class btConvexHullComputer; - - public: - int getSourceVertex() const - { - return (this + reverse)->targetVertex; - } - - int getTargetVertex() const - { - return targetVertex; - } - - const Edge* getNextEdgeOfVertex() const // clockwise list of all edges of a vertex - { - return this + next; - } - - const Edge* getNextEdgeOfFace() const // counter-clockwise list of all edges of a face - { - return (this + reverse)->getNextEdgeOfVertex(); - } - - const Edge* getReverseEdge() const - { - return this + reverse; - } - }; - - // Vertices of the output hull - btAlignedObjectArray vertices; - - // Edges of the output hull - btAlignedObjectArray edges; - - // Faces of the convex hull. Each entry is an index into the "edges" array pointing to an edge of the face. Faces are planar n-gons - btAlignedObjectArray faces; - - /* - Compute convex hull of "count" vertices stored in "coords". "stride" is the difference in bytes - between the addresses of consecutive vertices. If "shrink" is positive, the convex hull is shrunken - by that amount (each face is moved by "shrink" length units towards the center along its normal). - If "shrinkClamp" is positive, "shrink" is clamped to not exceed "shrinkClamp * innerRadius", where "innerRadius" - is the minimum distance of a face to the center of the convex hull. - - The returned value is the amount by which the hull has been shrunken. If it is negative, the amount was so large - that the resulting convex hull is empty. - - The output convex hull can be found in the member variables "vertices", "edges", "faces". - */ - btScalar compute(const float* coords, int stride, int count, btScalar shrink, btScalar shrinkClamp) - { - return compute(coords, false, stride, count, shrink, shrinkClamp); - } - - // same as above, but double precision - btScalar compute(const double* coords, int stride, int count, btScalar shrink, btScalar shrinkClamp) - { - return compute(coords, true, stride, count, shrink, shrinkClamp); - } -}; - -#endif //BT_CONVEX_HULL_COMPUTER_H diff --git a/extern/bullet/src/Extras/VHACD/inc/btMinMax.h b/extern/bullet/src/Extras/VHACD/inc/btMinMax.h deleted file mode 100644 index 40b0ceb6eda0..000000000000 --- a/extern/bullet/src/Extras/VHACD/inc/btMinMax.h +++ /dev/null @@ -1,65 +0,0 @@ -/* -Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/ - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#ifndef BT_GEN_MINMAX_H -#define BT_GEN_MINMAX_H - -#include "btScalar.h" - -template -SIMD_FORCE_INLINE const T& btMin(const T& a, const T& b) -{ - return a < b ? a : b; -} - -template -SIMD_FORCE_INLINE const T& btMax(const T& a, const T& b) -{ - return a > b ? a : b; -} - -template -SIMD_FORCE_INLINE const T& btClamped(const T& a, const T& lb, const T& ub) -{ - return a < lb ? lb : (ub < a ? ub : a); -} - -template -SIMD_FORCE_INLINE void btSetMin(T& a, const T& b) -{ - if (b < a) { - a = b; - } -} - -template -SIMD_FORCE_INLINE void btSetMax(T& a, const T& b) -{ - if (a < b) { - a = b; - } -} - -template -SIMD_FORCE_INLINE void btClamp(T& a, const T& lb, const T& ub) -{ - if (a < lb) { - a = lb; - } - else if (ub < a) { - a = ub; - } -} - -#endif //BT_GEN_MINMAX_H diff --git a/extern/bullet/src/Extras/VHACD/inc/btScalar.h b/extern/bullet/src/Extras/VHACD/inc/btScalar.h deleted file mode 100644 index ad3032497be1..000000000000 --- a/extern/bullet/src/Extras/VHACD/inc/btScalar.h +++ /dev/null @@ -1,532 +0,0 @@ -/* -Copyright (c) 2003-2009 Erwin Coumans http://bullet.googlecode.com - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#ifndef BT_SCALAR_H -#define BT_SCALAR_H - -#ifdef BT_MANAGED_CODE -//Aligned data types not supported in managed code -#pragma unmanaged -#endif - -#include -#include -#include //size_t for MSVC 6.0 - -/* SVN $Revision$ on $Date$ from http://bullet.googlecode.com*/ -#define BT_BULLET_VERSION 279 - -inline int btGetVersion() -{ - return BT_BULLET_VERSION; -} - -#if defined(DEBUG) || defined(_DEBUG) -#define BT_DEBUG -#endif - -#ifdef _WIN32 - -#if defined(__MINGW32__) || defined(__CYGWIN__) || (defined(_MSC_VER) && _MSC_VER < 1300) - -#define SIMD_FORCE_INLINE inline -#define ATTRIBUTE_ALIGNED16(a) a -#define ATTRIBUTE_ALIGNED64(a) a -#define ATTRIBUTE_ALIGNED128(a) a -#else -//#define BT_HAS_ALIGNED_ALLOCATOR -#pragma warning(disable : 4324) // disable padding warning -// #pragma warning(disable:4530) // Disable the exception disable but used in MSCV Stl warning. -// #pragma warning(disable:4996) //Turn off warnings about deprecated C routines -// #pragma warning(disable:4786) // Disable the "debug name too long" warning - -#define SIMD_FORCE_INLINE __forceinline -#define ATTRIBUTE_ALIGNED16(a) __declspec(align(16)) a -#define ATTRIBUTE_ALIGNED64(a) __declspec(align(64)) a -#define ATTRIBUTE_ALIGNED128(a) __declspec(align(128)) a -#ifdef _XBOX -#define BT_USE_VMX128 - -#include -#define BT_HAVE_NATIVE_FSEL -#define btFsel(a, b, c) __fsel((a), (b), (c)) -#else - -#if (defined(_WIN32) && (_MSC_VER) && _MSC_VER >= 1400) && (!defined(BT_USE_DOUBLE_PRECISION)) -#define BT_USE_SSE -#include -#endif - -#endif //_XBOX - -#endif //__MINGW32__ - -#include -#ifdef BT_DEBUG -#define btAssert assert -#else -#define btAssert(x) -#endif -//btFullAssert is optional, slows down a lot -#define btFullAssert(x) - -#define btLikely(_c) _c -#define btUnlikely(_c) _c - -#else - -#if defined(__CELLOS_LV2__) -#define SIMD_FORCE_INLINE inline __attribute__((always_inline)) -#define ATTRIBUTE_ALIGNED16(a) a __attribute__((aligned(16))) -#define ATTRIBUTE_ALIGNED64(a) a __attribute__((aligned(64))) -#define ATTRIBUTE_ALIGNED128(a) a __attribute__((aligned(128))) -#ifndef assert -#include -#endif -#ifdef BT_DEBUG -#ifdef __SPU__ -#include -#define printf spu_printf -#define btAssert(x) \ - { \ - if (!(x)) { \ - printf("Assert " __FILE__ ":%u (" #x ")\n", __LINE__); \ - spu_hcmpeq(0, 0); \ - } \ - } -#else -#define btAssert assert -#endif - -#else -#define btAssert(x) -#endif -//btFullAssert is optional, slows down a lot -#define btFullAssert(x) - -#define btLikely(_c) _c -#define btUnlikely(_c) _c - -#else - -#ifdef USE_LIBSPE2 - -#define SIMD_FORCE_INLINE __inline -#define ATTRIBUTE_ALIGNED16(a) a __attribute__((aligned(16))) -#define ATTRIBUTE_ALIGNED64(a) a __attribute__((aligned(64))) -#define ATTRIBUTE_ALIGNED128(a) a __attribute__((aligned(128))) -#ifndef assert -#include -#endif -#ifdef BT_DEBUG -#define btAssert assert -#else -#define btAssert(x) -#endif -//btFullAssert is optional, slows down a lot -#define btFullAssert(x) - -#define btLikely(_c) __builtin_expect((_c), 1) -#define btUnlikely(_c) __builtin_expect((_c), 0) - -#else -//non-windows systems - -#if (defined(__APPLE__) && defined(__i386__) && (!defined(BT_USE_DOUBLE_PRECISION))) -#define BT_USE_SSE -#include - -#define SIMD_FORCE_INLINE inline -///@todo: check out alignment methods for other platforms/compilers -#define ATTRIBUTE_ALIGNED16(a) a __attribute__((aligned(16))) -#define ATTRIBUTE_ALIGNED64(a) a __attribute__((aligned(64))) -#define ATTRIBUTE_ALIGNED128(a) a __attribute__((aligned(128))) -#ifndef assert -#include -#endif - -#if defined(DEBUG) || defined(_DEBUG) -#define btAssert assert -#else -#define btAssert(x) -#endif - -//btFullAssert is optional, slows down a lot -#define btFullAssert(x) -#define btLikely(_c) _c -#define btUnlikely(_c) _c - -#else - -#define SIMD_FORCE_INLINE inline -///@todo: check out alignment methods for other platforms/compilers -///#define ATTRIBUTE_ALIGNED16(a) a __attribute__ ((aligned (16))) -///#define ATTRIBUTE_ALIGNED64(a) a __attribute__ ((aligned (64))) -///#define ATTRIBUTE_ALIGNED128(a) a __attribute__ ((aligned (128))) -#define ATTRIBUTE_ALIGNED16(a) a -#define ATTRIBUTE_ALIGNED64(a) a -#define ATTRIBUTE_ALIGNED128(a) a -#ifndef assert -#include -#endif - -#if defined(DEBUG) || defined(_DEBUG) -#define btAssert assert -#else -#define btAssert(x) -#endif - -//btFullAssert is optional, slows down a lot -#define btFullAssert(x) -#define btLikely(_c) _c -#define btUnlikely(_c) _c -#endif //__APPLE__ - -#endif // LIBSPE2 - -#endif //__CELLOS_LV2__ -#endif - -///The btScalar type abstracts floating point numbers, to easily switch between double and single floating point precision. -#if defined(BT_USE_DOUBLE_PRECISION) -typedef double btScalar; -//this number could be bigger in double precision -#define BT_LARGE_FLOAT 1e30 -#else -typedef float btScalar; -//keep BT_LARGE_FLOAT*BT_LARGE_FLOAT < FLT_MAX -#define BT_LARGE_FLOAT 1e18f -#endif - -#define BT_DECLARE_ALIGNED_ALLOCATOR() \ - SIMD_FORCE_INLINE void* operator new(size_t sizeInBytes) { return btAlignedAlloc(sizeInBytes, 16); } \ - SIMD_FORCE_INLINE void operator delete(void* ptr) { btAlignedFree(ptr); } \ - SIMD_FORCE_INLINE void* operator new(size_t, void* ptr) { return ptr; } \ - SIMD_FORCE_INLINE void operator delete(void*, void*) {} \ - SIMD_FORCE_INLINE void* operator new[](size_t sizeInBytes) { return btAlignedAlloc(sizeInBytes, 16); } \ - SIMD_FORCE_INLINE void operator delete[](void* ptr) { btAlignedFree(ptr); } \ - SIMD_FORCE_INLINE void* operator new[](size_t, void* ptr) { return ptr; } \ - SIMD_FORCE_INLINE void operator delete[](void*, void*) {} - -#if defined(BT_USE_DOUBLE_PRECISION) || defined(BT_FORCE_DOUBLE_FUNCTIONS) - -SIMD_FORCE_INLINE btScalar btSqrt(btScalar x) -{ - return sqrt(x); -} -SIMD_FORCE_INLINE btScalar btFabs(btScalar x) { return fabs(x); } -SIMD_FORCE_INLINE btScalar btCos(btScalar x) { return cos(x); } -SIMD_FORCE_INLINE btScalar btSin(btScalar x) { return sin(x); } -SIMD_FORCE_INLINE btScalar btTan(btScalar x) { return tan(x); } -SIMD_FORCE_INLINE btScalar btAcos(btScalar x) -{ - if (x < btScalar(-1)) - x = btScalar(-1); - if (x > btScalar(1)) - x = btScalar(1); - return acos(x); -} -SIMD_FORCE_INLINE btScalar btAsin(btScalar x) -{ - if (x < btScalar(-1)) - x = btScalar(-1); - if (x > btScalar(1)) - x = btScalar(1); - return asin(x); -} -SIMD_FORCE_INLINE btScalar btAtan(btScalar x) { return atan(x); } -SIMD_FORCE_INLINE btScalar btAtan2(btScalar x, btScalar y) { return atan2(x, y); } -SIMD_FORCE_INLINE btScalar btExp(btScalar x) { return exp(x); } -SIMD_FORCE_INLINE btScalar btLog(btScalar x) { return log(x); } -SIMD_FORCE_INLINE btScalar btPow(btScalar x, btScalar y) { return pow(x, y); } -SIMD_FORCE_INLINE btScalar btFmod(btScalar x, btScalar y) { return fmod(x, y); } - -#else - -SIMD_FORCE_INLINE btScalar btSqrt(btScalar y) -{ -#ifdef USE_APPROXIMATION - double x, z, tempf; - unsigned long* tfptr = ((unsigned long*)&tempf) + 1; - - tempf = y; - *tfptr = (0xbfcdd90a - *tfptr) >> 1; /* estimate of 1/sqrt(y) */ - x = tempf; - z = y * btScalar(0.5); - x = (btScalar(1.5) * x) - (x * x) * (x * z); /* iteration formula */ - x = (btScalar(1.5) * x) - (x * x) * (x * z); - x = (btScalar(1.5) * x) - (x * x) * (x * z); - x = (btScalar(1.5) * x) - (x * x) * (x * z); - x = (btScalar(1.5) * x) - (x * x) * (x * z); - return x * y; -#else - return sqrtf(y); -#endif -} -SIMD_FORCE_INLINE btScalar btFabs(btScalar x) { return fabsf(x); } -SIMD_FORCE_INLINE btScalar btCos(btScalar x) { return cosf(x); } -SIMD_FORCE_INLINE btScalar btSin(btScalar x) { return sinf(x); } -SIMD_FORCE_INLINE btScalar btTan(btScalar x) { return tanf(x); } -SIMD_FORCE_INLINE btScalar btAcos(btScalar x) -{ - if (x < btScalar(-1)) - x = btScalar(-1); - if (x > btScalar(1)) - x = btScalar(1); - return acosf(x); -} -SIMD_FORCE_INLINE btScalar btAsin(btScalar x) -{ - if (x < btScalar(-1)) - x = btScalar(-1); - if (x > btScalar(1)) - x = btScalar(1); - return asinf(x); -} -SIMD_FORCE_INLINE btScalar btAtan(btScalar x) { return atanf(x); } -SIMD_FORCE_INLINE btScalar btAtan2(btScalar x, btScalar y) { return atan2f(x, y); } -SIMD_FORCE_INLINE btScalar btExp(btScalar x) { return expf(x); } -SIMD_FORCE_INLINE btScalar btLog(btScalar x) { return logf(x); } -SIMD_FORCE_INLINE btScalar btPow(btScalar x, btScalar y) { return powf(x, y); } -SIMD_FORCE_INLINE btScalar btFmod(btScalar x, btScalar y) { return fmodf(x, y); } - -#endif - -#define SIMD_2_PI btScalar(6.283185307179586232) -#define SIMD_PI (SIMD_2_PI * btScalar(0.5)) -#define SIMD_HALF_PI (SIMD_2_PI * btScalar(0.25)) -#define SIMD_RADS_PER_DEG (SIMD_2_PI / btScalar(360.0)) -#define SIMD_DEGS_PER_RAD (btScalar(360.0) / SIMD_2_PI) -#define SIMDSQRT12 btScalar(0.7071067811865475244008443621048490) - -#define btRecipSqrt(x) ((btScalar)(btScalar(1.0) / btSqrt(btScalar(x)))) /* reciprocal square root */ - -#ifdef BT_USE_DOUBLE_PRECISION -#define SIMD_EPSILON DBL_EPSILON -#define SIMD_INFINITY DBL_MAX -#else -#define SIMD_EPSILON FLT_EPSILON -#define SIMD_INFINITY FLT_MAX -#endif - -SIMD_FORCE_INLINE btScalar btAtan2Fast(btScalar y, btScalar x) -{ - btScalar coeff_1 = SIMD_PI / 4.0f; - btScalar coeff_2 = 3.0f * coeff_1; - btScalar abs_y = btFabs(y); - btScalar angle; - if (x >= 0.0f) { - btScalar r = (x - abs_y) / (x + abs_y); - angle = coeff_1 - coeff_1 * r; - } - else { - btScalar r = (x + abs_y) / (abs_y - x); - angle = coeff_2 - coeff_1 * r; - } - return (y < 0.0f) ? -angle : angle; -} - -SIMD_FORCE_INLINE bool btFuzzyZero(btScalar x) { return btFabs(x) < SIMD_EPSILON; } - -SIMD_FORCE_INLINE bool btEqual(btScalar a, btScalar eps) -{ - return (((a) <= eps) && !((a) < -eps)); -} -SIMD_FORCE_INLINE bool btGreaterEqual(btScalar a, btScalar eps) -{ - return (!((a) <= eps)); -} - -SIMD_FORCE_INLINE int btIsNegative(btScalar x) -{ - return x < btScalar(0.0) ? 1 : 0; -} - -SIMD_FORCE_INLINE btScalar btRadians(btScalar x) { return x * SIMD_RADS_PER_DEG; } -SIMD_FORCE_INLINE btScalar btDegrees(btScalar x) { return x * SIMD_DEGS_PER_RAD; } - -#define BT_DECLARE_HANDLE(name) \ - typedef struct name##__ { \ - int unused; \ - } * name - -#ifndef btFsel -SIMD_FORCE_INLINE btScalar btFsel(btScalar a, btScalar b, btScalar c) -{ - return a >= 0 ? b : c; -} -#endif -#define btFsels(a, b, c) (btScalar) btFsel(a, b, c) - -SIMD_FORCE_INLINE bool btMachineIsLittleEndian() -{ - long int i = 1; - const char* p = (const char*)&i; - if (p[0] == 1) // Lowest address contains the least significant byte - return true; - else - return false; -} - -///btSelect avoids branches, which makes performance much better for consoles like Playstation 3 and XBox 360 -///Thanks Phil Knight. See also http://www.cellperformance.com/articles/2006/04/more_techniques_for_eliminatin_1.html -SIMD_FORCE_INLINE unsigned btSelect(unsigned condition, unsigned valueIfConditionNonZero, unsigned valueIfConditionZero) -{ - // Set testNz to 0xFFFFFFFF if condition is nonzero, 0x00000000 if condition is zero - // Rely on positive value or'ed with its negative having sign bit on - // and zero value or'ed with its negative (which is still zero) having sign bit off - // Use arithmetic shift right, shifting the sign bit through all 32 bits - unsigned testNz = (unsigned)(((int)condition | -(int)condition) >> 31); - unsigned testEqz = ~testNz; - return ((valueIfConditionNonZero & testNz) | (valueIfConditionZero & testEqz)); -} -SIMD_FORCE_INLINE int btSelect(unsigned condition, int valueIfConditionNonZero, int valueIfConditionZero) -{ - unsigned testNz = (unsigned)(((int)condition | -(int)condition) >> 31); - unsigned testEqz = ~testNz; - return static_cast((valueIfConditionNonZero & testNz) | (valueIfConditionZero & testEqz)); -} -SIMD_FORCE_INLINE float btSelect(unsigned condition, float valueIfConditionNonZero, float valueIfConditionZero) -{ -#ifdef BT_HAVE_NATIVE_FSEL - return (float)btFsel((btScalar)condition - btScalar(1.0f), valueIfConditionNonZero, valueIfConditionZero); -#else - return (condition != 0) ? valueIfConditionNonZero : valueIfConditionZero; -#endif -} - -template -SIMD_FORCE_INLINE void btSwap(T& a, T& b) -{ - T tmp = a; - a = b; - b = tmp; -} - -//PCK: endian swapping functions -SIMD_FORCE_INLINE unsigned btSwapEndian(unsigned val) -{ - return (((val & 0xff000000) >> 24) | ((val & 0x00ff0000) >> 8) | ((val & 0x0000ff00) << 8) | ((val & 0x000000ff) << 24)); -} - -SIMD_FORCE_INLINE unsigned short btSwapEndian(unsigned short val) -{ - return static_cast(((val & 0xff00) >> 8) | ((val & 0x00ff) << 8)); -} - -SIMD_FORCE_INLINE unsigned btSwapEndian(int val) -{ - return btSwapEndian((unsigned)val); -} - -SIMD_FORCE_INLINE unsigned short btSwapEndian(short val) -{ - return btSwapEndian((unsigned short)val); -} - -///btSwapFloat uses using char pointers to swap the endianness -////btSwapFloat/btSwapDouble will NOT return a float, because the machine might 'correct' invalid floating point values -///Not all values of sign/exponent/mantissa are valid floating point numbers according to IEEE 754. -///When a floating point unit is faced with an invalid value, it may actually change the value, or worse, throw an exception. -///In most systems, running user mode code, you wouldn't get an exception, but instead the hardware/os/runtime will 'fix' the number for you. -///so instead of returning a float/double, we return integer/long long integer -SIMD_FORCE_INLINE unsigned int btSwapEndianFloat(float d) -{ - unsigned int a = 0; - unsigned char* dst = (unsigned char*)&a; - unsigned char* src = (unsigned char*)&d; - - dst[0] = src[3]; - dst[1] = src[2]; - dst[2] = src[1]; - dst[3] = src[0]; - return a; -} - -// unswap using char pointers -SIMD_FORCE_INLINE float btUnswapEndianFloat(unsigned int a) -{ - float d = 0.0f; - unsigned char* src = (unsigned char*)&a; - unsigned char* dst = (unsigned char*)&d; - - dst[0] = src[3]; - dst[1] = src[2]; - dst[2] = src[1]; - dst[3] = src[0]; - - return d; -} - -// swap using char pointers -SIMD_FORCE_INLINE void btSwapEndianDouble(double d, unsigned char* dst) -{ - unsigned char* src = (unsigned char*)&d; - - dst[0] = src[7]; - dst[1] = src[6]; - dst[2] = src[5]; - dst[3] = src[4]; - dst[4] = src[3]; - dst[5] = src[2]; - dst[6] = src[1]; - dst[7] = src[0]; -} - -// unswap using char pointers -SIMD_FORCE_INLINE double btUnswapEndianDouble(const unsigned char* src) -{ - double d = 0.0; - unsigned char* dst = (unsigned char*)&d; - - dst[0] = src[7]; - dst[1] = src[6]; - dst[2] = src[5]; - dst[3] = src[4]; - dst[4] = src[3]; - dst[5] = src[2]; - dst[6] = src[1]; - dst[7] = src[0]; - - return d; -} - -// returns normalized value in range [-SIMD_PI, SIMD_PI] -SIMD_FORCE_INLINE btScalar btNormalizeAngle(btScalar angleInRadians) -{ - angleInRadians = btFmod(angleInRadians, SIMD_2_PI); - if (angleInRadians < -SIMD_PI) { - return angleInRadians + SIMD_2_PI; - } - else if (angleInRadians > SIMD_PI) { - return angleInRadians - SIMD_2_PI; - } - else { - return angleInRadians; - } -} - -///rudimentary class to provide type info -struct btTypedObject { - btTypedObject(int objectType) - : m_objectType(objectType) - { - } - int m_objectType; - inline int getObjectType() const - { - return m_objectType; - } -}; -#endif //BT_SCALAR_H diff --git a/extern/bullet/src/Extras/VHACD/inc/btVector3.h b/extern/bullet/src/Extras/VHACD/inc/btVector3.h deleted file mode 100644 index 159d67bdda7d..000000000000 --- a/extern/bullet/src/Extras/VHACD/inc/btVector3.h +++ /dev/null @@ -1,715 +0,0 @@ -/* -Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/ - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#ifndef BT_VECTOR3_H -#define BT_VECTOR3_H - -#include "btMinMax.h" -#include "btScalar.h" - -#ifdef BT_USE_DOUBLE_PRECISION -#define btVector3Data btVector3DoubleData -#define btVector3DataName "btVector3DoubleData" -#else -#define btVector3Data btVector3FloatData -#define btVector3DataName "btVector3FloatData" -#endif //BT_USE_DOUBLE_PRECISION - -/**@brief btVector3 can be used to represent 3D points and vectors. - * It has an un-used w component to suit 16-byte alignment when btVector3 is stored in containers. This extra component can be used by derived classes (Quaternion?) or by user - * Ideally, this class should be replaced by a platform optimized SIMD version that keeps the data in registers - */ -ATTRIBUTE_ALIGNED16(class) -btVector3 -{ -public: -#if defined(__SPU__) && defined(__CELLOS_LV2__) - btScalar m_floats[4]; - -public: - SIMD_FORCE_INLINE const vec_float4& get128() const - { - return *((const vec_float4*)&m_floats[0]); - } - -public: -#else //__CELLOS_LV2__ __SPU__ -#ifdef BT_USE_SSE // _WIN32 - union { - __m128 mVec128; - btScalar m_floats[4]; - }; - SIMD_FORCE_INLINE __m128 get128() const - { - return mVec128; - } - SIMD_FORCE_INLINE void set128(__m128 v128) - { - mVec128 = v128; - } -#else - btScalar m_floats[4]; -#endif -#endif //__CELLOS_LV2__ __SPU__ - -public: - /**@brief No initialization constructor */ - SIMD_FORCE_INLINE btVector3() {} - - /**@brief Constructor from scalars - * @param x X value - * @param y Y value - * @param z Z value - */ - SIMD_FORCE_INLINE btVector3(const btScalar& x, const btScalar& y, const btScalar& z) - { - m_floats[0] = x; - m_floats[1] = y; - m_floats[2] = z; - m_floats[3] = btScalar(0.); - } - - /**@brief Add a vector to this one - * @param The vector to add to this one */ - SIMD_FORCE_INLINE btVector3& operator+=(const btVector3& v) - { - - m_floats[0] += v.m_floats[0]; - m_floats[1] += v.m_floats[1]; - m_floats[2] += v.m_floats[2]; - return *this; - } - - /**@brief Subtract a vector from this one - * @param The vector to subtract */ - SIMD_FORCE_INLINE btVector3& operator-=(const btVector3& v) - { - m_floats[0] -= v.m_floats[0]; - m_floats[1] -= v.m_floats[1]; - m_floats[2] -= v.m_floats[2]; - return *this; - } - /**@brief Scale the vector - * @param s Scale factor */ - SIMD_FORCE_INLINE btVector3& operator*=(const btScalar& s) - { - m_floats[0] *= s; - m_floats[1] *= s; - m_floats[2] *= s; - return *this; - } - - /**@brief Inversely scale the vector - * @param s Scale factor to divide by */ - SIMD_FORCE_INLINE btVector3& operator/=(const btScalar& s) - { - btFullAssert(s != btScalar(0.0)); - return * this *= btScalar(1.0) / s; - } - - /**@brief Return the dot product - * @param v The other vector in the dot product */ - SIMD_FORCE_INLINE btScalar dot(const btVector3& v) const - { - return m_floats[0] * v.m_floats[0] + m_floats[1] * v.m_floats[1] + m_floats[2] * v.m_floats[2]; - } - - /**@brief Return the length of the vector squared */ - SIMD_FORCE_INLINE btScalar length2() const - { - return dot(*this); - } - - /**@brief Return the length of the vector */ - SIMD_FORCE_INLINE btScalar length() const - { - return btSqrt(length2()); - } - - /**@brief Return the distance squared between the ends of this and another vector - * This is symantically treating the vector like a point */ - SIMD_FORCE_INLINE btScalar distance2(const btVector3& v) const; - - /**@brief Return the distance between the ends of this and another vector - * This is symantically treating the vector like a point */ - SIMD_FORCE_INLINE btScalar distance(const btVector3& v) const; - - SIMD_FORCE_INLINE btVector3& safeNormalize() - { - btVector3 absVec = this->absolute(); - int maxIndex = absVec.maxAxis(); - if (absVec[maxIndex] > 0) { - *this /= absVec[maxIndex]; - return * this /= length(); - } - setValue(1, 0, 0); - return *this; - } - - /**@brief Normalize this vector - * x^2 + y^2 + z^2 = 1 */ - SIMD_FORCE_INLINE btVector3& normalize() - { - return * this /= length(); - } - - /**@brief Return a normalized version of this vector */ - SIMD_FORCE_INLINE btVector3 normalized() const; - - /**@brief Return a rotated version of this vector - * @param wAxis The axis to rotate about - * @param angle The angle to rotate by */ - SIMD_FORCE_INLINE btVector3 rotate(const btVector3& wAxis, const btScalar angle) const; - - /**@brief Return the angle between this and another vector - * @param v The other vector */ - SIMD_FORCE_INLINE btScalar angle(const btVector3& v) const - { - btScalar s = btSqrt(length2() * v.length2()); - btFullAssert(s != btScalar(0.0)); - return btAcos(dot(v) / s); - } - /**@brief Return a vector will the absolute values of each element */ - SIMD_FORCE_INLINE btVector3 absolute() const - { - return btVector3( - btFabs(m_floats[0]), - btFabs(m_floats[1]), - btFabs(m_floats[2])); - } - /**@brief Return the cross product between this and another vector - * @param v The other vector */ - SIMD_FORCE_INLINE btVector3 cross(const btVector3& v) const - { - return btVector3( - m_floats[1] * v.m_floats[2] - m_floats[2] * v.m_floats[1], - m_floats[2] * v.m_floats[0] - m_floats[0] * v.m_floats[2], - m_floats[0] * v.m_floats[1] - m_floats[1] * v.m_floats[0]); - } - - SIMD_FORCE_INLINE btScalar triple(const btVector3& v1, const btVector3& v2) const - { - return m_floats[0] * (v1.m_floats[1] * v2.m_floats[2] - v1.m_floats[2] * v2.m_floats[1]) + m_floats[1] * (v1.m_floats[2] * v2.m_floats[0] - v1.m_floats[0] * v2.m_floats[2]) + m_floats[2] * (v1.m_floats[0] * v2.m_floats[1] - v1.m_floats[1] * v2.m_floats[0]); - } - - /**@brief Return the axis with the smallest value - * Note return values are 0,1,2 for x, y, or z */ - SIMD_FORCE_INLINE int minAxis() const - { - return m_floats[0] < m_floats[1] ? (m_floats[0] < m_floats[2] ? 0 : 2) : (m_floats[1] < m_floats[2] ? 1 : 2); - } - - /**@brief Return the axis with the largest value - * Note return values are 0,1,2 for x, y, or z */ - SIMD_FORCE_INLINE int maxAxis() const - { - return m_floats[0] < m_floats[1] ? (m_floats[1] < m_floats[2] ? 2 : 1) : (m_floats[0] < m_floats[2] ? 2 : 0); - } - - SIMD_FORCE_INLINE int furthestAxis() const - { - return absolute().minAxis(); - } - - SIMD_FORCE_INLINE int closestAxis() const - { - return absolute().maxAxis(); - } - - SIMD_FORCE_INLINE void setInterpolate3(const btVector3& v0, const btVector3& v1, btScalar rt) - { - btScalar s = btScalar(1.0) - rt; - m_floats[0] = s * v0.m_floats[0] + rt * v1.m_floats[0]; - m_floats[1] = s * v0.m_floats[1] + rt * v1.m_floats[1]; - m_floats[2] = s * v0.m_floats[2] + rt * v1.m_floats[2]; - //don't do the unused w component - // m_co[3] = s * v0[3] + rt * v1[3]; - } - - /**@brief Return the linear interpolation between this and another vector - * @param v The other vector - * @param t The ration of this to v (t = 0 => return this, t=1 => return other) */ - SIMD_FORCE_INLINE btVector3 lerp(const btVector3& v, const btScalar& t) const - { - return btVector3(m_floats[0] + (v.m_floats[0] - m_floats[0]) * t, - m_floats[1] + (v.m_floats[1] - m_floats[1]) * t, - m_floats[2] + (v.m_floats[2] - m_floats[2]) * t); - } - - /**@brief Elementwise multiply this vector by the other - * @param v The other vector */ - SIMD_FORCE_INLINE btVector3& operator*=(const btVector3& v) - { - m_floats[0] *= v.m_floats[0]; - m_floats[1] *= v.m_floats[1]; - m_floats[2] *= v.m_floats[2]; - return *this; - } - - /**@brief Return the x value */ - SIMD_FORCE_INLINE const btScalar& getX() const { return m_floats[0]; } - /**@brief Return the y value */ - SIMD_FORCE_INLINE const btScalar& getY() const { return m_floats[1]; } - /**@brief Return the z value */ - SIMD_FORCE_INLINE const btScalar& getZ() const { return m_floats[2]; } - /**@brief Set the x value */ - SIMD_FORCE_INLINE void setX(btScalar x) { m_floats[0] = x; }; - /**@brief Set the y value */ - SIMD_FORCE_INLINE void setY(btScalar y) { m_floats[1] = y; }; - /**@brief Set the z value */ - SIMD_FORCE_INLINE void setZ(btScalar z) { m_floats[2] = z; }; - /**@brief Set the w value */ - SIMD_FORCE_INLINE void setW(btScalar w) { m_floats[3] = w; }; - /**@brief Return the x value */ - SIMD_FORCE_INLINE const btScalar& x() const { return m_floats[0]; } - /**@brief Return the y value */ - SIMD_FORCE_INLINE const btScalar& y() const { return m_floats[1]; } - /**@brief Return the z value */ - SIMD_FORCE_INLINE const btScalar& z() const { return m_floats[2]; } - /**@brief Return the w value */ - SIMD_FORCE_INLINE const btScalar& w() const { return m_floats[3]; } - - //SIMD_FORCE_INLINE btScalar& operator[](int i) { return (&m_floats[0])[i]; } - //SIMD_FORCE_INLINE const btScalar& operator[](int i) const { return (&m_floats[0])[i]; } - ///operator btScalar*() replaces operator[], using implicit conversion. We added operator != and operator == to avoid pointer comparisons. - SIMD_FORCE_INLINE operator btScalar*() { return &m_floats[0]; } - SIMD_FORCE_INLINE operator const btScalar*() const { return &m_floats[0]; } - - SIMD_FORCE_INLINE bool operator==(const btVector3& other) const - { - return ((m_floats[3] == other.m_floats[3]) && (m_floats[2] == other.m_floats[2]) && (m_floats[1] == other.m_floats[1]) && (m_floats[0] == other.m_floats[0])); - } - - SIMD_FORCE_INLINE bool operator!=(const btVector3& other) const - { - return !(*this == other); - } - - /**@brief Set each element to the max of the current values and the values of another btVector3 - * @param other The other btVector3 to compare with - */ - SIMD_FORCE_INLINE void setMax(const btVector3& other) - { - btSetMax(m_floats[0], other.m_floats[0]); - btSetMax(m_floats[1], other.m_floats[1]); - btSetMax(m_floats[2], other.m_floats[2]); - btSetMax(m_floats[3], other.w()); - } - /**@brief Set each element to the min of the current values and the values of another btVector3 - * @param other The other btVector3 to compare with - */ - SIMD_FORCE_INLINE void setMin(const btVector3& other) - { - btSetMin(m_floats[0], other.m_floats[0]); - btSetMin(m_floats[1], other.m_floats[1]); - btSetMin(m_floats[2], other.m_floats[2]); - btSetMin(m_floats[3], other.w()); - } - - SIMD_FORCE_INLINE void setValue(const btScalar& x, const btScalar& y, const btScalar& z) - { - m_floats[0] = x; - m_floats[1] = y; - m_floats[2] = z; - m_floats[3] = btScalar(0.); - } - - void getSkewSymmetricMatrix(btVector3 * v0, btVector3 * v1, btVector3 * v2) const - { - v0->setValue(0., -z(), y()); - v1->setValue(z(), 0., -x()); - v2->setValue(-y(), x(), 0.); - } - - void setZero() - { - setValue(btScalar(0.), btScalar(0.), btScalar(0.)); - } - - SIMD_FORCE_INLINE bool isZero() const - { - return m_floats[0] == btScalar(0) && m_floats[1] == btScalar(0) && m_floats[2] == btScalar(0); - } - - SIMD_FORCE_INLINE bool fuzzyZero() const - { - return length2() < SIMD_EPSILON; - } - - SIMD_FORCE_INLINE void serialize(struct btVector3Data & dataOut) const; - - SIMD_FORCE_INLINE void deSerialize(const struct btVector3Data& dataIn); - - SIMD_FORCE_INLINE void serializeFloat(struct btVector3FloatData & dataOut) const; - - SIMD_FORCE_INLINE void deSerializeFloat(const struct btVector3FloatData& dataIn); - - SIMD_FORCE_INLINE void serializeDouble(struct btVector3DoubleData & dataOut) const; - - SIMD_FORCE_INLINE void deSerializeDouble(const struct btVector3DoubleData& dataIn); -}; - -/**@brief Return the sum of two vectors (Point symantics)*/ -SIMD_FORCE_INLINE btVector3 -operator+(const btVector3& v1, const btVector3& v2) -{ - return btVector3(v1.m_floats[0] + v2.m_floats[0], v1.m_floats[1] + v2.m_floats[1], v1.m_floats[2] + v2.m_floats[2]); -} - -/**@brief Return the elementwise product of two vectors */ -SIMD_FORCE_INLINE btVector3 -operator*(const btVector3& v1, const btVector3& v2) -{ - return btVector3(v1.m_floats[0] * v2.m_floats[0], v1.m_floats[1] * v2.m_floats[1], v1.m_floats[2] * v2.m_floats[2]); -} - -/**@brief Return the difference between two vectors */ -SIMD_FORCE_INLINE btVector3 -operator-(const btVector3& v1, const btVector3& v2) -{ - return btVector3(v1.m_floats[0] - v2.m_floats[0], v1.m_floats[1] - v2.m_floats[1], v1.m_floats[2] - v2.m_floats[2]); -} -/**@brief Return the negative of the vector */ -SIMD_FORCE_INLINE btVector3 -operator-(const btVector3& v) -{ - return btVector3(-v.m_floats[0], -v.m_floats[1], -v.m_floats[2]); -} - -/**@brief Return the vector scaled by s */ -SIMD_FORCE_INLINE btVector3 -operator*(const btVector3& v, const btScalar& s) -{ - return btVector3(v.m_floats[0] * s, v.m_floats[1] * s, v.m_floats[2] * s); -} - -/**@brief Return the vector scaled by s */ -SIMD_FORCE_INLINE btVector3 -operator*(const btScalar& s, const btVector3& v) -{ - return v * s; -} - -/**@brief Return the vector inversely scaled by s */ -SIMD_FORCE_INLINE btVector3 -operator/(const btVector3& v, const btScalar& s) -{ - btFullAssert(s != btScalar(0.0)); - return v * (btScalar(1.0) / s); -} - -/**@brief Return the vector inversely scaled by s */ -SIMD_FORCE_INLINE btVector3 -operator/(const btVector3& v1, const btVector3& v2) -{ - return btVector3(v1.m_floats[0] / v2.m_floats[0], v1.m_floats[1] / v2.m_floats[1], v1.m_floats[2] / v2.m_floats[2]); -} - -/**@brief Return the dot product between two vectors */ -SIMD_FORCE_INLINE btScalar -btDot(const btVector3& v1, const btVector3& v2) -{ - return v1.dot(v2); -} - -/**@brief Return the distance squared between two vectors */ -SIMD_FORCE_INLINE btScalar -btDistance2(const btVector3& v1, const btVector3& v2) -{ - return v1.distance2(v2); -} - -/**@brief Return the distance between two vectors */ -SIMD_FORCE_INLINE btScalar -btDistance(const btVector3& v1, const btVector3& v2) -{ - return v1.distance(v2); -} - -/**@brief Return the angle between two vectors */ -SIMD_FORCE_INLINE btScalar -btAngle(const btVector3& v1, const btVector3& v2) -{ - return v1.angle(v2); -} - -/**@brief Return the cross product of two vectors */ -SIMD_FORCE_INLINE btVector3 -btCross(const btVector3& v1, const btVector3& v2) -{ - return v1.cross(v2); -} - -SIMD_FORCE_INLINE btScalar -btTriple(const btVector3& v1, const btVector3& v2, const btVector3& v3) -{ - return v1.triple(v2, v3); -} - -/**@brief Return the linear interpolation between two vectors - * @param v1 One vector - * @param v2 The other vector - * @param t The ration of this to v (t = 0 => return v1, t=1 => return v2) */ -SIMD_FORCE_INLINE btVector3 -lerp(const btVector3& v1, const btVector3& v2, const btScalar& t) -{ - return v1.lerp(v2, t); -} - -SIMD_FORCE_INLINE btScalar btVector3::distance2(const btVector3& v) const -{ - return (v - *this).length2(); -} - -SIMD_FORCE_INLINE btScalar btVector3::distance(const btVector3& v) const -{ - return (v - *this).length(); -} - -SIMD_FORCE_INLINE btVector3 btVector3::normalized() const -{ - return *this / length(); -} - -SIMD_FORCE_INLINE btVector3 btVector3::rotate(const btVector3& wAxis, const btScalar angle) const -{ - // wAxis must be a unit lenght vector - - btVector3 o = wAxis * wAxis.dot(*this); - btVector3 x = *this - o; - btVector3 y; - - y = wAxis.cross(*this); - - return (o + x * btCos(angle) + y * btSin(angle)); -} - -class btVector4 : public btVector3 { -public: - SIMD_FORCE_INLINE btVector4() {} - - SIMD_FORCE_INLINE btVector4(const btScalar& x, const btScalar& y, const btScalar& z, const btScalar& w) - : btVector3(x, y, z) - { - m_floats[3] = w; - } - - SIMD_FORCE_INLINE btVector4 absolute4() const - { - return btVector4( - btFabs(m_floats[0]), - btFabs(m_floats[1]), - btFabs(m_floats[2]), - btFabs(m_floats[3])); - } - - btScalar getW() const { return m_floats[3]; } - - SIMD_FORCE_INLINE int maxAxis4() const - { - int maxIndex = -1; - btScalar maxVal = btScalar(-BT_LARGE_FLOAT); - if (m_floats[0] > maxVal) { - maxIndex = 0; - maxVal = m_floats[0]; - } - if (m_floats[1] > maxVal) { - maxIndex = 1; - maxVal = m_floats[1]; - } - if (m_floats[2] > maxVal) { - maxIndex = 2; - maxVal = m_floats[2]; - } - if (m_floats[3] > maxVal) { - maxIndex = 3; - } - return maxIndex; - } - - SIMD_FORCE_INLINE int minAxis4() const - { - int minIndex = -1; - btScalar minVal = btScalar(BT_LARGE_FLOAT); - if (m_floats[0] < minVal) { - minIndex = 0; - minVal = m_floats[0]; - } - if (m_floats[1] < minVal) { - minIndex = 1; - minVal = m_floats[1]; - } - if (m_floats[2] < minVal) { - minIndex = 2; - minVal = m_floats[2]; - } - if (m_floats[3] < minVal) { - minIndex = 3; - } - - return minIndex; - } - - SIMD_FORCE_INLINE int closestAxis4() const - { - return absolute4().maxAxis4(); - } - - /**@brief Set x,y,z and zero w - * @param x Value of x - * @param y Value of y - * @param z Value of z - */ - - /* void getValue(btScalar *m) const - { - m[0] = m_floats[0]; - m[1] = m_floats[1]; - m[2] =m_floats[2]; - } -*/ - /**@brief Set the values - * @param x Value of x - * @param y Value of y - * @param z Value of z - * @param w Value of w - */ - SIMD_FORCE_INLINE void setValue(const btScalar& x, const btScalar& y, const btScalar& z, const btScalar& w) - { - m_floats[0] = x; - m_floats[1] = y; - m_floats[2] = z; - m_floats[3] = w; - } -}; - -///btSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization -SIMD_FORCE_INLINE void btSwapScalarEndian(const btScalar& sourceVal, btScalar& destVal) -{ -#ifdef BT_USE_DOUBLE_PRECISION - unsigned char* dest = (unsigned char*)&destVal; - unsigned char* src = (unsigned char*)&sourceVal; - dest[0] = src[7]; - dest[1] = src[6]; - dest[2] = src[5]; - dest[3] = src[4]; - dest[4] = src[3]; - dest[5] = src[2]; - dest[6] = src[1]; - dest[7] = src[0]; -#else - unsigned char* dest = (unsigned char*)&destVal; - unsigned char* src = (unsigned char*)&sourceVal; - dest[0] = src[3]; - dest[1] = src[2]; - dest[2] = src[1]; - dest[3] = src[0]; -#endif //BT_USE_DOUBLE_PRECISION -} -///btSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization -SIMD_FORCE_INLINE void btSwapVector3Endian(const btVector3& sourceVec, btVector3& destVec) -{ - for (int i = 0; i < 4; i++) { - btSwapScalarEndian(sourceVec[i], destVec[i]); - } -} - -///btUnSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization -SIMD_FORCE_INLINE void btUnSwapVector3Endian(btVector3& vector) -{ - - btVector3 swappedVec; - for (int i = 0; i < 4; i++) { - btSwapScalarEndian(vector[i], swappedVec[i]); - } - vector = swappedVec; -} - -template -SIMD_FORCE_INLINE void btPlaneSpace1(const T& n, T& p, T& q) -{ - if (btFabs(n[2]) > SIMDSQRT12) { - // choose p in y-z plane - btScalar a = n[1] * n[1] + n[2] * n[2]; - btScalar k = btRecipSqrt(a); - p[0] = 0; - p[1] = -n[2] * k; - p[2] = n[1] * k; - // set q = n x p - q[0] = a * k; - q[1] = -n[0] * p[2]; - q[2] = n[0] * p[1]; - } - else { - // choose p in x-y plane - btScalar a = n[0] * n[0] + n[1] * n[1]; - btScalar k = btRecipSqrt(a); - p[0] = -n[1] * k; - p[1] = n[0] * k; - p[2] = 0; - // set q = n x p - q[0] = -n[2] * p[1]; - q[1] = n[2] * p[0]; - q[2] = a * k; - } -} - -struct btVector3FloatData { - float m_floats[4]; -}; - -struct btVector3DoubleData { - double m_floats[4]; -}; - -SIMD_FORCE_INLINE void btVector3::serializeFloat(struct btVector3FloatData& dataOut) const -{ - ///could also do a memcpy, check if it is worth it - for (int i = 0; i < 4; i++) - dataOut.m_floats[i] = float(m_floats[i]); -} - -SIMD_FORCE_INLINE void btVector3::deSerializeFloat(const struct btVector3FloatData& dataIn) -{ - for (int i = 0; i < 4; i++) - m_floats[i] = btScalar(dataIn.m_floats[i]); -} - -SIMD_FORCE_INLINE void btVector3::serializeDouble(struct btVector3DoubleData& dataOut) const -{ - ///could also do a memcpy, check if it is worth it - for (int i = 0; i < 4; i++) - dataOut.m_floats[i] = double(m_floats[i]); -} - -SIMD_FORCE_INLINE void btVector3::deSerializeDouble(const struct btVector3DoubleData& dataIn) -{ - for (int i = 0; i < 4; i++) - m_floats[i] = btScalar(dataIn.m_floats[i]); -} - -SIMD_FORCE_INLINE void btVector3::serialize(struct btVector3Data& dataOut) const -{ - ///could also do a memcpy, check if it is worth it - for (int i = 0; i < 4; i++) - dataOut.m_floats[i] = m_floats[i]; -} - -SIMD_FORCE_INLINE void btVector3::deSerialize(const struct btVector3Data& dataIn) -{ - for (int i = 0; i < 4; i++) - m_floats[i] = dataIn.m_floats[i]; -} - -#endif //BT_VECTOR3_H diff --git a/extern/bullet/src/Extras/VHACD/inc/vhacdCircularList.h b/extern/bullet/src/Extras/VHACD/inc/vhacdCircularList.h deleted file mode 100644 index 0f5ddf9ecfaa..000000000000 --- a/extern/bullet/src/Extras/VHACD/inc/vhacdCircularList.h +++ /dev/null @@ -1,79 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) - All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#pragma once -#ifndef VHACD_CIRCULAR_LIST_H -#define VHACD_CIRCULAR_LIST_H -#include -namespace VHACD { -//! CircularListElement class. -template -class CircularListElement { -public: - T& GetData() { return m_data; } - const T& GetData() const { return m_data; } - CircularListElement*& GetNext() { return m_next; } - CircularListElement*& GetPrev() { return m_prev; } - const CircularListElement*& GetNext() const { return m_next; } - const CircularListElement*& GetPrev() const { return m_prev; } - //! Constructor - CircularListElement(const T& data) { m_data = data; } - CircularListElement(void) {} - //! Destructor - ~CircularListElement(void) {} -private: - T m_data; - CircularListElement* m_next; - CircularListElement* m_prev; - - CircularListElement(const CircularListElement& rhs); -}; -//! CircularList class. -template -class CircularList { -public: - CircularListElement*& GetHead() { return m_head; } - const CircularListElement* GetHead() const { return m_head; } - bool IsEmpty() const { return (m_size == 0); } - size_t GetSize() const { return m_size; } - const T& GetData() const { return m_head->GetData(); } - T& GetData() { return m_head->GetData(); } - bool Delete(); - bool Delete(CircularListElement* element); - CircularListElement* Add(const T* data = 0); - CircularListElement* Add(const T& data); - bool Next(); - bool Prev(); - void Clear() - { - while (Delete()) - ; - }; - const CircularList& operator=(const CircularList& rhs); - //! Constructor - CircularList() - { - m_head = 0; - m_size = 0; - } - CircularList(const CircularList& rhs); - //! Destructor - ~CircularList(void) { Clear(); }; -private: - CircularListElement* m_head; //!< a pointer to the head of the circular list - size_t m_size; //!< number of element in the circular list -}; -} -#include "vhacdCircularList.inl" -#endif // VHACD_CIRCULAR_LIST_H \ No newline at end of file diff --git a/extern/bullet/src/Extras/VHACD/inc/vhacdCircularList.inl b/extern/bullet/src/Extras/VHACD/inc/vhacdCircularList.inl deleted file mode 100644 index 2be5180524e2..000000000000 --- a/extern/bullet/src/Extras/VHACD/inc/vhacdCircularList.inl +++ /dev/null @@ -1,161 +0,0 @@ -#pragma once -#ifndef HACD_CIRCULAR_LIST_INL -#define HACD_CIRCULAR_LIST_INL -namespace VHACD -{ - template < typename T > - inline bool CircularList::Delete(CircularListElement * element) - { - if (!element) - { - return false; - } - if (m_size > 1) - { - CircularListElement * next = element->GetNext(); - CircularListElement * prev = element->GetPrev(); - delete element; - m_size--; - if (element == m_head) - { - m_head = next; - } - next->GetPrev() = prev; - prev->GetNext() = next; - return true; - } - else if (m_size == 1) - { - delete m_head; - m_size--; - m_head = 0; - return true; - } - else - { - return false; - } - } - - template < typename T > - inline bool CircularList::Delete() - { - if (m_size > 1) - { - CircularListElement * next = m_head->GetNext(); - CircularListElement * prev = m_head->GetPrev(); - delete m_head; - m_size--; - m_head = next; - next->GetPrev() = prev; - prev->GetNext() = next; - return true; - } - else if (m_size == 1) - { - delete m_head; - m_size--; - m_head = 0; - return true; - } - else - { - return false; - } - } - template < typename T > - inline CircularListElement * CircularList::Add(const T * data) - { - if (m_size == 0) - { - if (data) - { - m_head = new CircularListElement(*data); - } - else - { - m_head = new CircularListElement(); - } - m_head->GetNext() = m_head->GetPrev() = m_head; - } - else - { - CircularListElement * next = m_head->GetNext(); - CircularListElement * element = m_head; - if (data) - { - m_head = new CircularListElement(*data); - } - else - { - m_head = new CircularListElement(); - } - m_head->GetNext() = next; - m_head->GetPrev() = element; - element->GetNext() = m_head; - next->GetPrev() = m_head; - } - m_size++; - return m_head; - } - template < typename T > - inline CircularListElement * CircularList::Add(const T & data) - { - const T * pData = &data; - return Add(pData); - } - template < typename T > - inline bool CircularList::Next() - { - if (m_size == 0) - { - return false; - } - m_head = m_head->GetNext(); - return true; - } - template < typename T > - inline bool CircularList::Prev() - { - if (m_size == 0) - { - return false; - } - m_head = m_head->GetPrev(); - return true; - } - template < typename T > - inline CircularList::CircularList(const CircularList& rhs) - { - if (rhs.m_size > 0) - { - CircularListElement * current = rhs.m_head; - do - { - current = current->GetNext(); - Add(current->GetData()); - } - while ( current != rhs.m_head ); - } - } - template < typename T > - inline const CircularList& CircularList::operator=(const CircularList& rhs) - { - if (&rhs != this) - { - Clear(); - if (rhs.m_size > 0) - { - CircularListElement * current = rhs.m_head; - do - { - current = current->GetNext(); - Add(current->GetData()); - } - while ( current != rhs.m_head ); - } - } - return (*this); - } -} -#endif \ No newline at end of file diff --git a/extern/bullet/src/Extras/VHACD/inc/vhacdICHull.h b/extern/bullet/src/Extras/VHACD/inc/vhacdICHull.h deleted file mode 100644 index a3d941651af0..000000000000 --- a/extern/bullet/src/Extras/VHACD/inc/vhacdICHull.h +++ /dev/null @@ -1,98 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) - All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#pragma once -#ifndef VHACD_ICHULL_H -#define VHACD_ICHULL_H -#include "vhacdManifoldMesh.h" -#include "vhacdVector.h" - -namespace VHACD { -//! Incremental Convex Hull algorithm (cf. http://cs.smith.edu/~orourke/books/ftp.html ). -enum ICHullError { - ICHullErrorOK = 0, - ICHullErrorCoplanarPoints, - ICHullErrorNoVolume, - ICHullErrorInconsistent, - ICHullErrorNotEnoughPoints -}; -class ICHull { -public: - static const double sc_eps; - //! - bool IsFlat() { return m_isFlat; } - //! Returns the computed mesh - TMMesh& GetMesh() { return m_mesh; } - //! Add one point to the convex-hull - bool AddPoint(const Vec3& point) { return AddPoints(&point, 1); } - //! Add one point to the convex-hull - bool AddPoint(const Vec3& point, int id); - //! Add points to the convex-hull - bool AddPoints(const Vec3* points, size_t nPoints); - //! - ICHullError Process(); - //! - ICHullError Process(const unsigned int nPointsCH, const double minVolume = 0.0); - //! - bool IsInside(const Vec3& pt0, const double eps = 0.0); - //! - const ICHull& operator=(ICHull& rhs); - - //! Constructor - ICHull(); - //! Destructor - ~ICHull(void){}; - -private: - //! DoubleTriangle builds the initial double triangle. It first finds 3 noncollinear points and makes two faces out of them, in opposite order. It then finds a fourth point that is not coplanar with that face. The vertices are stored in the face structure in counterclockwise order so that the volume between the face and the point is negative. Lastly, the 3 newfaces to the fourth point are constructed and the data structures are cleaned up. - ICHullError DoubleTriangle(); - //! MakeFace creates a new face structure from three vertices (in ccw order). It returns a pointer to the face. - CircularListElement* MakeFace(CircularListElement* v0, - CircularListElement* v1, - CircularListElement* v2, - CircularListElement* fold); - //! - CircularListElement* MakeConeFace(CircularListElement* e, CircularListElement* v); - //! - bool ProcessPoint(); - //! - bool ComputePointVolume(double& totalVolume, bool markVisibleFaces); - //! - bool FindMaxVolumePoint(const double minVolume = 0.0); - //! - bool CleanEdges(); - //! - bool CleanVertices(unsigned int& addedPoints); - //! - bool CleanTriangles(); - //! - bool CleanUp(unsigned int& addedPoints); - //! - bool MakeCCW(CircularListElement* f, - CircularListElement* e, - CircularListElement* v); - void Clear(); - -private: - static const int sc_dummyIndex; - TMMesh m_mesh; - SArray*> m_edgesToDelete; - SArray*> m_edgesToUpdate; - SArray*> m_trianglesToDelete; - Vec3 m_normal; - bool m_isFlat; - ICHull(const ICHull& rhs); -}; -} -#endif // VHACD_ICHULL_H diff --git a/extern/bullet/src/Extras/VHACD/inc/vhacdManifoldMesh.h b/extern/bullet/src/Extras/VHACD/inc/vhacdManifoldMesh.h deleted file mode 100644 index f178ad3d56f0..000000000000 --- a/extern/bullet/src/Extras/VHACD/inc/vhacdManifoldMesh.h +++ /dev/null @@ -1,142 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) -All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -*/ -#pragma once -#ifndef VHACD_MANIFOLD_MESH_H -#define VHACD_MANIFOLD_MESH_H -#include "vhacdCircularList.h" -#include "vhacdSArray.h" -#include "vhacdVector.h" -namespace VHACD { -class TMMTriangle; -class TMMEdge; -class TMMesh; -class ICHull; - -//! Vertex data structure used in a triangular manifold mesh (TMM). -class TMMVertex { -public: - void Initialize(); - TMMVertex(void); - ~TMMVertex(void); - -private: - Vec3 m_pos; - int m_name; - size_t m_id; - CircularListElement* m_duplicate; // pointer to incident cone edge (or NULL) - bool m_onHull; - bool m_tag; - TMMVertex(const TMMVertex& rhs); - friend class ICHull; - friend class TMMesh; - friend class TMMTriangle; - friend class TMMEdge; -}; - -//! Edge data structure used in a triangular manifold mesh (TMM). -class TMMEdge { -public: - void Initialize(); - TMMEdge(void); - ~TMMEdge(void); - -private: - size_t m_id; - CircularListElement* m_triangles[2]; - CircularListElement* m_vertices[2]; - CircularListElement* m_newFace; - TMMEdge(const TMMEdge& rhs); - friend class ICHull; - friend class TMMTriangle; - friend class TMMVertex; - friend class TMMesh; -}; - -//! Triangle data structure used in a triangular manifold mesh (TMM). -class TMMTriangle { -public: - void Initialize(); - TMMTriangle(void); - ~TMMTriangle(void); - -private: - size_t m_id; - CircularListElement* m_edges[3]; - CircularListElement* m_vertices[3]; - bool m_visible; - - TMMTriangle(const TMMTriangle& rhs); - friend class ICHull; - friend class TMMesh; - friend class TMMVertex; - friend class TMMEdge; -}; -//! triangular manifold mesh data structure. -class TMMesh { -public: - //! Returns the number of vertices> - inline size_t GetNVertices() const { return m_vertices.GetSize(); } - //! Returns the number of edges - inline size_t GetNEdges() const { return m_edges.GetSize(); } - //! Returns the number of triangles - inline size_t GetNTriangles() const { return m_triangles.GetSize(); } - //! Returns the vertices circular list - inline const CircularList& GetVertices() const { return m_vertices; } - //! Returns the edges circular list - inline const CircularList& GetEdges() const { return m_edges; } - //! Returns the triangles circular list - inline const CircularList& GetTriangles() const { return m_triangles; } - //! Returns the vertices circular list - inline CircularList& GetVertices() { return m_vertices; } - //! Returns the edges circular list - inline CircularList& GetEdges() { return m_edges; } - //! Returns the triangles circular list - inline CircularList& GetTriangles() { return m_triangles; } - //! Add vertex to the mesh - CircularListElement* AddVertex() { return m_vertices.Add(); } - //! Add vertex to the mesh - CircularListElement* AddEdge() { return m_edges.Add(); } - //! Add vertex to the mesh - CircularListElement* AddTriangle() { return m_triangles.Add(); } - //! Print mesh information - void Print(); - //! - void GetIFS(Vec3* const points, Vec3* const triangles); - //! - void Clear(); - //! - void Copy(TMMesh& mesh); - //! - bool CheckConsistancy(); - //! - bool Normalize(); - //! - bool Denormalize(); - //! Constructor - TMMesh(); - //! Destructor - virtual ~TMMesh(void); - -private: - CircularList m_vertices; - CircularList m_edges; - CircularList m_triangles; - - // not defined - TMMesh(const TMMesh& rhs); - friend class ICHull; -}; -} -#endif // VHACD_MANIFOLD_MESH_H \ No newline at end of file diff --git a/extern/bullet/src/Extras/VHACD/inc/vhacdMesh.h b/extern/bullet/src/Extras/VHACD/inc/vhacdMesh.h deleted file mode 100644 index 0975d8e1f4ef..000000000000 --- a/extern/bullet/src/Extras/VHACD/inc/vhacdMesh.h +++ /dev/null @@ -1,129 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) - All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#pragma once -#ifndef VHACD_MESH_H -#define VHACD_MESH_H -#include "vhacdSArray.h" -#include "vhacdVector.h" - -#define VHACD_DEBUG_MESH - -namespace VHACD { -enum AXIS { - AXIS_X = 0, - AXIS_Y = 1, - AXIS_Z = 2 -}; -struct Plane { - double m_a; - double m_b; - double m_c; - double m_d; - AXIS m_axis; - short m_index; -}; -#ifdef VHACD_DEBUG_MESH -struct Material { - - Vec3 m_diffuseColor; - double m_ambientIntensity; - Vec3 m_specularColor; - Vec3 m_emissiveColor; - double m_shininess; - double m_transparency; - Material(void) - { - m_diffuseColor.X() = 0.5; - m_diffuseColor.Y() = 0.5; - m_diffuseColor.Z() = 0.5; - m_specularColor.X() = 0.5; - m_specularColor.Y() = 0.5; - m_specularColor.Z() = 0.5; - m_ambientIntensity = 0.4; - m_emissiveColor.X() = 0.0; - m_emissiveColor.Y() = 0.0; - m_emissiveColor.Z() = 0.0; - m_shininess = 0.4; - m_transparency = 0.0; - }; -}; -#endif // VHACD_DEBUG_MESH - -//! Triangular mesh data structure -class Mesh { -public: - void AddPoint(const Vec3& pt) { m_points.PushBack(pt); }; - void SetPoint(size_t index, const Vec3& pt) { m_points[index] = pt; }; - const Vec3& GetPoint(size_t index) const { return m_points[index]; }; - Vec3& GetPoint(size_t index) { return m_points[index]; }; - size_t GetNPoints() const { return m_points.Size(); }; - double* GetPoints() { return (double*)m_points.Data(); } // ugly - const double* const GetPoints() const { return (double*)m_points.Data(); } // ugly - const Vec3* const GetPointsBuffer() const { return m_points.Data(); } // - Vec3* const GetPointsBuffer() { return m_points.Data(); } // - void AddTriangle(const Vec3& tri) { m_triangles.PushBack(tri); }; - void SetTriangle(size_t index, const Vec3& tri) { m_triangles[index] = tri; }; - const Vec3& GetTriangle(size_t index) const { return m_triangles[index]; }; - Vec3& GetTriangle(size_t index) { return m_triangles[index]; }; - size_t GetNTriangles() const { return m_triangles.Size(); }; - int* GetTriangles() { return (int*)m_triangles.Data(); } // ugly - const int* const GetTriangles() const { return (int*)m_triangles.Data(); } // ugly - const Vec3* const GetTrianglesBuffer() const { return m_triangles.Data(); } - Vec3* const GetTrianglesBuffer() { return m_triangles.Data(); } - const Vec3& GetCenter() const { return m_center; } - const Vec3& GetMinBB() const { return m_minBB; } - const Vec3& GetMaxBB() const { return m_maxBB; } - void ClearPoints() { m_points.Clear(); } - void ClearTriangles() { m_triangles.Clear(); } - void Clear() - { - ClearPoints(); - ClearTriangles(); - } - void ResizePoints(size_t nPts) { m_points.Resize(nPts); } - void ResizeTriangles(size_t nTri) { m_triangles.Resize(nTri); } - void CopyPoints(SArray >& points) const { points = m_points; } - double GetDiagBB() const { return m_diag; } - double ComputeVolume() const; - void ComputeConvexHull(const double* const pts, - const size_t nPts); - void Clip(const Plane& plane, - SArray >& positivePart, - SArray >& negativePart) const; - bool IsInside(const Vec3& pt) const; - double ComputeDiagBB(); - -#ifdef VHACD_DEBUG_MESH - bool LoadOFF(const std::string& fileName, bool invert); - bool SaveVRML2(const std::string& fileName) const; - bool SaveVRML2(std::ofstream& fout, const Material& material) const; - bool SaveOFF(const std::string& fileName) const; -#endif // VHACD_DEBUG_MESH - - //! Constructor. - Mesh(); - //! Destructor. - ~Mesh(void); - -private: - SArray > m_points; - SArray > m_triangles; - Vec3 m_minBB; - Vec3 m_maxBB; - Vec3 m_center; - double m_diag; -}; -} -#endif \ No newline at end of file diff --git a/extern/bullet/src/Extras/VHACD/inc/vhacdMutex.h b/extern/bullet/src/Extras/VHACD/inc/vhacdMutex.h deleted file mode 100644 index a28f6be61ef0..000000000000 --- a/extern/bullet/src/Extras/VHACD/inc/vhacdMutex.h +++ /dev/null @@ -1,146 +0,0 @@ -/*! -** -** Copyright (c) 2009 by John W. Ratcliff mailto:jratcliffscarab@gmail.com -** -** Portions of this source has been released with the PhysXViewer application, as well as -** Rocket, CreateDynamics, ODF, and as a number of sample code snippets. -** -** If you find this code useful or you are feeling particularily generous I would -** ask that you please go to http://www.amillionpixels.us and make a donation -** to Troy DeMolay. -** -** DeMolay is a youth group for young men between the ages of 12 and 21. -** It teaches strong moral principles, as well as leadership skills and -** public speaking. The donations page uses the 'pay for pixels' paradigm -** where, in this case, a pixel is only a single penny. Donations can be -** made for as small as $4 or as high as a $100 block. Each person who donates -** will get a link to their own site as well as acknowledgement on the -** donations blog located here http://www.amillionpixels.blogspot.com/ -** -** If you wish to contact me you can use the following methods: -** -** Skype ID: jratcliff63367 -** Yahoo: jratcliff63367 -** AOL: jratcliff1961 -** email: jratcliffscarab@gmail.com -** -** -** The MIT license: -** -** Permission is hereby granted, free of charge, to any person obtaining a copy -** of this software and associated documentation files (the "Software"), to deal -** in the Software without restriction, including without limitation the rights -** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -** copies of the Software, and to permit persons to whom the Software is furnished -** to do so, subject to the following conditions: -** -** The above copyright notice and this permission notice shall be included in all -** copies or substantial portions of the Software. - -** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, -** WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN -** CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - -*/ - -#pragma once -#ifndef VHACD_MUTEX_H -#define VHACD_MUTEX_H - -#if defined(WIN32) - -//#define _WIN32_WINNT 0x400 -#include -#pragma comment(lib, "winmm.lib") -#endif - -#if defined(__linux__) -//#include -#include -#include -#include -#define __stdcall -#endif - -#if defined(__APPLE__) || defined(__linux__) -#include -#endif - -#if defined(__APPLE__) -#define PTHREAD_MUTEX_RECURSIVE_NP PTHREAD_MUTEX_RECURSIVE -#endif - -#define VHACD_DEBUG - -//#define VHACD_NDEBUG -#ifdef VHACD_NDEBUG -#define VHACD_VERIFY(x) (x) -#else -#define VHACD_VERIFY(x) assert((x)) -#endif - -namespace VHACD { -class Mutex { -public: - Mutex(void) - { -#if defined(WIN32) || defined(_XBOX) - InitializeCriticalSection(&m_mutex); -#elif defined(__APPLE__) || defined(__linux__) - pthread_mutexattr_t mutexAttr; // Mutex Attribute - VHACD_VERIFY(pthread_mutexattr_init(&mutexAttr) == 0); - VHACD_VERIFY(pthread_mutexattr_settype(&mutexAttr, PTHREAD_MUTEX_RECURSIVE_NP) == 0); - VHACD_VERIFY(pthread_mutex_init(&m_mutex, &mutexAttr) == 0); - VHACD_VERIFY(pthread_mutexattr_destroy(&mutexAttr) == 0); -#endif - } - ~Mutex(void) - { -#if defined(WIN32) || defined(_XBOX) - DeleteCriticalSection(&m_mutex); -#elif defined(__APPLE__) || defined(__linux__) - VHACD_VERIFY(pthread_mutex_destroy(&m_mutex) == 0); -#endif - } - void Lock(void) - { -#if defined(WIN32) || defined(_XBOX) - EnterCriticalSection(&m_mutex); -#elif defined(__APPLE__) || defined(__linux__) - VHACD_VERIFY(pthread_mutex_lock(&m_mutex) == 0); -#endif - } - bool TryLock(void) - { -#if defined(WIN32) || defined(_XBOX) - bool bRet = false; - //assert(("TryEnterCriticalSection seems to not work on XP???", 0)); - bRet = TryEnterCriticalSection(&m_mutex) ? true : false; - return bRet; -#elif defined(__APPLE__) || defined(__linux__) - int result = pthread_mutex_trylock(&m_mutex); - return (result == 0); -#endif - } - - void Unlock(void) - { -#if defined(WIN32) || defined(_XBOX) - LeaveCriticalSection(&m_mutex); -#elif defined(__APPLE__) || defined(__linux__) - VHACD_VERIFY(pthread_mutex_unlock(&m_mutex) == 0); -#endif - } - -private: -#if defined(WIN32) || defined(_XBOX) - CRITICAL_SECTION m_mutex; -#elif defined(__APPLE__) || defined(__linux__) - pthread_mutex_t m_mutex; -#endif -}; -} -#endif // VHACD_MUTEX_H diff --git a/extern/bullet/src/Extras/VHACD/inc/vhacdSArray.h b/extern/bullet/src/Extras/VHACD/inc/vhacdSArray.h deleted file mode 100644 index 4d84d1ae267f..000000000000 --- a/extern/bullet/src/Extras/VHACD/inc/vhacdSArray.h +++ /dev/null @@ -1,158 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) - All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#pragma once -#ifndef VHACD_SARRAY_H -#define VHACD_SARRAY_H -#include -#include -#include - -#define SARRAY_DEFAULT_MIN_SIZE 16 - -namespace VHACD { -//! SArray. -template -class SArray { -public: - T& operator[](size_t i) - { - T* const data = Data(); - return data[i]; - } - const T& operator[](size_t i) const - { - const T* const data = Data(); - return data[i]; - } - size_t Size() const - { - return m_size; - } - T* const Data() - { - return (m_maxSize == N) ? m_data0 : m_data; - } - const T* const Data() const - { - return (m_maxSize == N) ? m_data0 : m_data; - } - void Clear() - { - m_size = 0; - delete[] m_data; - m_data = 0; - m_maxSize = N; - } - void PopBack() - { - --m_size; - } - void Allocate(size_t size) - { - if (size > m_maxSize) { - T* temp = new T[size]; - memcpy(temp, Data(), m_size * sizeof(T)); - delete[] m_data; - m_data = temp; - m_maxSize = size; - } - } - void Resize(size_t size) - { - Allocate(size); - m_size = size; - } - - void PushBack(const T& value) - { - if (m_size == m_maxSize) { - size_t maxSize = (m_maxSize << 1); - T* temp = new T[maxSize]; - memcpy(temp, Data(), m_maxSize * sizeof(T)); - delete[] m_data; - m_data = temp; - m_maxSize = maxSize; - } - T* const data = Data(); - data[m_size++] = value; - } - bool Find(const T& value, size_t& pos) - { - T* const data = Data(); - for (pos = 0; pos < m_size; ++pos) - if (value == data[pos]) - return true; - return false; - } - bool Insert(const T& value) - { - size_t pos; - if (Find(value, pos)) - return false; - PushBack(value); - return true; - } - bool Erase(const T& value) - { - size_t pos; - T* const data = Data(); - if (Find(value, pos)) { - for (size_t j = pos + 1; j < m_size; ++j) - data[j - 1] = data[j]; - --m_size; - return true; - } - return false; - } - void operator=(const SArray& rhs) - { - if (m_maxSize < rhs.m_size) { - delete[] m_data; - m_maxSize = rhs.m_maxSize; - m_data = new T[m_maxSize]; - } - m_size = rhs.m_size; - memcpy(Data(), rhs.Data(), m_size * sizeof(T)); - } - void Initialize() - { - m_data = 0; - m_size = 0; - m_maxSize = N; - } - SArray(const SArray& rhs) - { - m_data = 0; - m_size = 0; - m_maxSize = N; - *this = rhs; - } - SArray() - { - Initialize(); - } - ~SArray() - { - delete[] m_data; - } - -private: - T m_data0[N]; - T* m_data; - size_t m_size; - size_t m_maxSize; -}; -} -#endif \ No newline at end of file diff --git a/extern/bullet/src/Extras/VHACD/inc/vhacdTimer.h b/extern/bullet/src/Extras/VHACD/inc/vhacdTimer.h deleted file mode 100644 index ba0e2c336428..000000000000 --- a/extern/bullet/src/Extras/VHACD/inc/vhacdTimer.h +++ /dev/null @@ -1,121 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) - All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#pragma once -#ifndef VHACD_TIMER_H -#define VHACD_TIMER_H - -#ifdef _WIN32 -#ifndef WIN32_LEAN_AND_MEAN -#define WIN32_LEAN_AND_MEAN // Exclude rarely-used stuff from Windows headers -#endif -#include -#elif __MACH__ -#include -#include -#else -#include -#include -#endif - -namespace VHACD { -#ifdef _WIN32 -class Timer { -public: - Timer(void) - { - m_start.QuadPart = 0; - m_stop.QuadPart = 0; - QueryPerformanceFrequency(&m_freq); - }; - ~Timer(void){}; - void Tic() - { - QueryPerformanceCounter(&m_start); - } - void Toc() - { - QueryPerformanceCounter(&m_stop); - } - double GetElapsedTime() // in ms - { - LARGE_INTEGER delta; - delta.QuadPart = m_stop.QuadPart - m_start.QuadPart; - return (1000.0 * delta.QuadPart) / (double)m_freq.QuadPart; - } - -private: - LARGE_INTEGER m_start; - LARGE_INTEGER m_stop; - LARGE_INTEGER m_freq; -}; - -#elif __MACH__ -class Timer { -public: - Timer(void) - { - memset(this, 0, sizeof(Timer)); - host_get_clock_service(mach_host_self(), CALENDAR_CLOCK, &m_cclock); - }; - ~Timer(void) - { - mach_port_deallocate(mach_task_self(), m_cclock); - }; - void Tic() - { - clock_get_time(m_cclock, &m_start); - } - void Toc() - { - clock_get_time(m_cclock, &m_stop); - } - double GetElapsedTime() // in ms - { - return 1000.0 * (m_stop.tv_sec - m_start.tv_sec + (1.0E-9) * (m_stop.tv_nsec - m_start.tv_nsec)); - } - -private: - clock_serv_t m_cclock; - mach_timespec_t m_start; - mach_timespec_t m_stop; -}; -#else -class Timer { -public: - Timer(void) - { - memset(this, 0, sizeof(Timer)); - }; - ~Timer(void){}; - void Tic() - { - clock_gettime(CLOCK_REALTIME, &m_start); - } - void Toc() - { - clock_gettime(CLOCK_REALTIME, &m_stop); - } - double GetElapsedTime() // in ms - { - return 1000.0 * (m_stop.tv_sec - m_start.tv_sec + (1.0E-9) * (m_stop.tv_nsec - m_start.tv_nsec)); - } - -private: - struct timespec m_start; - struct timespec m_stop; -}; -#endif -} -#endif // VHACD_TIMER_H diff --git a/extern/bullet/src/Extras/VHACD/inc/vhacdVHACD.h b/extern/bullet/src/Extras/VHACD/inc/vhacdVHACD.h deleted file mode 100644 index 8c6c7fea1feb..000000000000 --- a/extern/bullet/src/Extras/VHACD/inc/vhacdVHACD.h +++ /dev/null @@ -1,350 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) -All rights reserved. - - -Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - -1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - -2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - -3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -*/ -#pragma once -#ifndef VHACD_VHACD_H -#define VHACD_VHACD_H - -#ifdef OPENCL_FOUND -#ifdef __MACH__ -#include -#else -#include -#endif -#endif //OPENCL_FOUND - -#include "vhacdMutex.h" -#include "vhacdVolume.h" - -#define USE_THREAD 1 -#define OCL_MIN_NUM_PRIMITIVES 4096 -#define CH_APP_MIN_NUM_PRIMITIVES 64000 -namespace VHACD { -class VHACD : public IVHACD { -public: - //! Constructor. - VHACD() - { -#if USE_THREAD == 1 && _OPENMP - m_ompNumProcessors = 2 * omp_get_num_procs(); - omp_set_num_threads(m_ompNumProcessors); -#else //USE_THREAD == 1 && _OPENMP - m_ompNumProcessors = 1; -#endif //USE_THREAD == 1 && _OPENMP -#ifdef CL_VERSION_1_1 - m_oclWorkGroupSize = 0; - m_oclDevice = 0; - m_oclQueue = 0; - m_oclKernelComputePartialVolumes = 0; - m_oclKernelComputeSum = 0; -#endif //CL_VERSION_1_1 - Init(); - } - //! Destructor. - ~VHACD(void) {} - unsigned int GetNConvexHulls() const - { - return (unsigned int)m_convexHulls.Size(); - } - void Cancel() - { - SetCancel(true); - } - void GetConvexHull(const unsigned int index, ConvexHull& ch) const - { - Mesh* mesh = m_convexHulls[index]; - ch.m_nPoints = (unsigned int)mesh->GetNPoints(); - ch.m_nTriangles = (unsigned int)mesh->GetNTriangles(); - ch.m_points = mesh->GetPoints(); - ch.m_triangles = mesh->GetTriangles(); - } - void Clean(void) - { - delete m_volume; - delete m_pset; - size_t nCH = m_convexHulls.Size(); - for (size_t p = 0; p < nCH; ++p) { - delete m_convexHulls[p]; - } - m_convexHulls.Clear(); - Init(); - } - void Release(void) - { - delete this; - } - bool Compute(const float* const points, - const unsigned int stridePoints, - const unsigned int nPoints, - const int* const triangles, - const unsigned int strideTriangles, - const unsigned int nTriangles, - const Parameters& params); - bool Compute(const double* const points, - const unsigned int stridePoints, - const unsigned int nPoints, - const int* const triangles, - const unsigned int strideTriangles, - const unsigned int nTriangles, - const Parameters& params); - bool OCLInit(void* const oclDevice, - IUserLogger* const logger = 0); - bool OCLRelease(IUserLogger* const logger = 0); - -private: - void SetCancel(bool cancel) - { - m_cancelMutex.Lock(); - m_cancel = cancel; - m_cancelMutex.Unlock(); - } - bool GetCancel() - { - - m_cancelMutex.Lock(); - bool cancel = m_cancel; - m_cancelMutex.Unlock(); - return cancel; - } - void Update(const double stageProgress, - const double operationProgress, - const Parameters& params) - { - m_stageProgress = stageProgress; - m_operationProgress = operationProgress; - if (params.m_callback) { - params.m_callback->Update(m_overallProgress, - m_stageProgress, - m_operationProgress, - m_stage.c_str(), - m_operation.c_str()); - } - } - void Init() - { - memset(m_rot, 0, sizeof(double) * 9); - m_dim = 64; - m_volume = 0; - m_volumeCH0 = 0.0; - m_pset = 0; - m_overallProgress = 0.0; - m_stageProgress = 0.0; - m_operationProgress = 0.0; - m_stage = ""; - m_operation = ""; - m_barycenter[0] = m_barycenter[1] = m_barycenter[2] = 0.0; - m_rot[0][0] = m_rot[1][1] = m_rot[2][2] = 1.0; - SetCancel(false); - } - void ComputePrimitiveSet(const Parameters& params); - void ComputeACD(const Parameters& params); - void MergeConvexHulls(const Parameters& params); - void SimplifyConvexHulls(const Parameters& params); - void ComputeBestClippingPlane(const PrimitiveSet* inputPSet, - const double volume, - const SArray& planes, - const Vec3& preferredCuttingDirection, - const double w, - const double alpha, - const double beta, - const int convexhullDownsampling, - const double progress0, - const double progress1, - Plane& bestPlane, - double& minConcavity, - const Parameters& params); - template - void AlignMesh(const T* const points, - const unsigned int stridePoints, - const unsigned int nPoints, - const int* const triangles, - const unsigned int strideTriangles, - const unsigned int nTriangles, - const Parameters& params) - { - if (GetCancel() || !params.m_pca) { - return; - } - m_timer.Tic(); - - m_stage = "Align mesh"; - m_operation = "Voxelization"; - - std::ostringstream msg; - if (params.m_logger) { - msg << "+ " << m_stage << std::endl; - params.m_logger->Log(msg.str().c_str()); - } - - Update(0.0, 0.0, params); - if (GetCancel()) { - return; - } - m_dim = (size_t)(pow((double)params.m_resolution, 1.0 / 3.0) + 0.5); - Volume volume; - volume.Voxelize(points, stridePoints, nPoints, - triangles, strideTriangles, nTriangles, - m_dim, m_barycenter, m_rot); - size_t n = volume.GetNPrimitivesOnSurf() + volume.GetNPrimitivesInsideSurf(); - Update(50.0, 100.0, params); - - if (params.m_logger) { - msg.str(""); - msg << "\t dim = " << m_dim << "\t-> " << n << " voxels" << std::endl; - params.m_logger->Log(msg.str().c_str()); - } - if (GetCancel()) { - return; - } - m_operation = "PCA"; - Update(50.0, 0.0, params); - volume.AlignToPrincipalAxes(m_rot); - m_overallProgress = 1.0; - Update(100.0, 100.0, params); - - m_timer.Toc(); - if (params.m_logger) { - msg.str(""); - msg << "\t time " << m_timer.GetElapsedTime() / 1000.0 << "s" << std::endl; - params.m_logger->Log(msg.str().c_str()); - } - } - template - void VoxelizeMesh(const T* const points, - const unsigned int stridePoints, - const unsigned int nPoints, - const int* const triangles, - const unsigned int strideTriangles, - const unsigned int nTriangles, - const Parameters& params) - { - if (GetCancel()) { - return; - } - - m_timer.Tic(); - m_stage = "Voxelization"; - - std::ostringstream msg; - if (params.m_logger) { - msg << "+ " << m_stage << std::endl; - params.m_logger->Log(msg.str().c_str()); - } - - delete m_volume; - m_volume = 0; - int iteration = 0; - const int maxIteration = 5; - double progress = 0.0; - while (iteration++ < maxIteration && !m_cancel) { - msg.str(""); - msg << "Iteration " << iteration; - m_operation = msg.str(); - - progress = iteration * 100.0 / maxIteration; - Update(progress, 0.0, params); - - m_volume = new Volume; - m_volume->Voxelize(points, stridePoints, nPoints, - triangles, strideTriangles, nTriangles, - m_dim, m_barycenter, m_rot); - - Update(progress, 100.0, params); - - size_t n = m_volume->GetNPrimitivesOnSurf() + m_volume->GetNPrimitivesInsideSurf(); - if (params.m_logger) { - msg.str(""); - msg << "\t dim = " << m_dim << "\t-> " << n << " voxels" << std::endl; - params.m_logger->Log(msg.str().c_str()); - } - - double a = pow((double)(params.m_resolution) / n, 0.33); - size_t dim_next = (size_t)(m_dim * a + 0.5); - if (n < params.m_resolution && iteration < maxIteration && m_volume->GetNPrimitivesOnSurf() < params.m_resolution / 8 && m_dim != dim_next) { - delete m_volume; - m_volume = 0; - m_dim = dim_next; - } - else { - break; - } - } - m_overallProgress = 10.0; - Update(100.0, 100.0, params); - - m_timer.Toc(); - if (params.m_logger) { - msg.str(""); - msg << "\t time " << m_timer.GetElapsedTime() / 1000.0 << "s" << std::endl; - params.m_logger->Log(msg.str().c_str()); - } - } - template - bool ComputeACD(const T* const points, - const unsigned int stridePoints, - const unsigned int nPoints, - const int* const triangles, - const unsigned int strideTriangles, - const unsigned int nTriangles, - const Parameters& params) - { - Init(); - if (params.m_oclAcceleration) { - // build kernals - } - AlignMesh(points, stridePoints, nPoints, triangles, strideTriangles, nTriangles, params); - VoxelizeMesh(points, stridePoints, nPoints, triangles, strideTriangles, nTriangles, params); - ComputePrimitiveSet(params); - ComputeACD(params); - MergeConvexHulls(params); - SimplifyConvexHulls(params); - if (params.m_oclAcceleration) { - // Release kernals - } - if (GetCancel()) { - Clean(); - return false; - } - return true; - } - -private: - SArray m_convexHulls; - std::string m_stage; - std::string m_operation; - double m_overallProgress; - double m_stageProgress; - double m_operationProgress; - double m_rot[3][3]; - double m_volumeCH0; - Vec3 m_barycenter; - Timer m_timer; - size_t m_dim; - Volume* m_volume; - PrimitiveSet* m_pset; - Mutex m_cancelMutex; - bool m_cancel; - int m_ompNumProcessors; -#ifdef CL_VERSION_1_1 - cl_device_id* m_oclDevice; - cl_context m_oclContext; - cl_program m_oclProgram; - cl_command_queue* m_oclQueue; - cl_kernel* m_oclKernelComputePartialVolumes; - cl_kernel* m_oclKernelComputeSum; - size_t m_oclWorkGroupSize; -#endif //CL_VERSION_1_1 -}; -} -#endif // VHACD_VHACD_H diff --git a/extern/bullet/src/Extras/VHACD/inc/vhacdVector.h b/extern/bullet/src/Extras/VHACD/inc/vhacdVector.h deleted file mode 100644 index c9edfb1ae769..000000000000 --- a/extern/bullet/src/Extras/VHACD/inc/vhacdVector.h +++ /dev/null @@ -1,103 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) - All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#pragma once -#ifndef VHACD_VECTOR_H -#define VHACD_VECTOR_H -#include -#include - -namespace VHACD { -//! Vector dim 3. -template -class Vec3 { -public: - T& operator[](size_t i) { return m_data[i]; } - const T& operator[](size_t i) const { return m_data[i]; } - T& X(); - T& Y(); - T& Z(); - const T& X() const; - const T& Y() const; - const T& Z() const; - void Normalize(); - T GetNorm() const; - void operator=(const Vec3& rhs); - void operator+=(const Vec3& rhs); - void operator-=(const Vec3& rhs); - void operator-=(T a); - void operator+=(T a); - void operator/=(T a); - void operator*=(T a); - Vec3 operator^(const Vec3& rhs) const; - T operator*(const Vec3& rhs) const; - Vec3 operator+(const Vec3& rhs) const; - Vec3 operator-(const Vec3& rhs) const; - Vec3 operator-() const; - Vec3 operator*(T rhs) const; - Vec3 operator/(T rhs) const; - bool operator<(const Vec3& rhs) const; - bool operator>(const Vec3& rhs) const; - Vec3(); - Vec3(T a); - Vec3(T x, T y, T z); - Vec3(const Vec3& rhs); - /*virtual*/ ~Vec3(void); - -private: - T m_data[3]; -}; -//! Vector dim 2. -template -class Vec2 { -public: - T& operator[](size_t i) { return m_data[i]; } - const T& operator[](size_t i) const { return m_data[i]; } - T& X(); - T& Y(); - const T& X() const; - const T& Y() const; - void Normalize(); - T GetNorm() const; - void operator=(const Vec2& rhs); - void operator+=(const Vec2& rhs); - void operator-=(const Vec2& rhs); - void operator-=(T a); - void operator+=(T a); - void operator/=(T a); - void operator*=(T a); - T operator^(const Vec2& rhs) const; - T operator*(const Vec2& rhs) const; - Vec2 operator+(const Vec2& rhs) const; - Vec2 operator-(const Vec2& rhs) const; - Vec2 operator-() const; - Vec2 operator*(T rhs) const; - Vec2 operator/(T rhs) const; - Vec2(); - Vec2(T a); - Vec2(T x, T y); - Vec2(const Vec2& rhs); - /*virtual*/ ~Vec2(void); - -private: - T m_data[2]; -}; - -template -const bool Colinear(const Vec3& a, const Vec3& b, const Vec3& c); -template -const T ComputeVolume4(const Vec3& a, const Vec3& b, const Vec3& c, const Vec3& d); -} -#include "vhacdVector.inl" // template implementation -#endif \ No newline at end of file diff --git a/extern/bullet/src/Extras/VHACD/inc/vhacdVector.inl b/extern/bullet/src/Extras/VHACD/inc/vhacdVector.inl deleted file mode 100644 index 223c2ef1734e..000000000000 --- a/extern/bullet/src/Extras/VHACD/inc/vhacdVector.inl +++ /dev/null @@ -1,362 +0,0 @@ -#pragma once -#ifndef VHACD_VECTOR_INL -#define VHACD_VECTOR_INL -namespace VHACD -{ - template - inline Vec3 operator*(T lhs, const Vec3 & rhs) - { - return Vec3(lhs * rhs.X(), lhs * rhs.Y(), lhs * rhs.Z()); - } - template - inline T & Vec3::X() - { - return m_data[0]; - } - template - inline T & Vec3::Y() - { - return m_data[1]; - } - template - inline T & Vec3::Z() - { - return m_data[2]; - } - template - inline const T & Vec3::X() const - { - return m_data[0]; - } - template - inline const T & Vec3::Y() const - { - return m_data[1]; - } - template - inline const T & Vec3::Z() const - { - return m_data[2]; - } - template - inline void Vec3::Normalize() - { - T n = sqrt(m_data[0]*m_data[0]+m_data[1]*m_data[1]+m_data[2]*m_data[2]); - if (n != 0.0) (*this) /= n; - } - template - inline T Vec3::GetNorm() const - { - return sqrt(m_data[0]*m_data[0]+m_data[1]*m_data[1]+m_data[2]*m_data[2]); - } - template - inline void Vec3::operator= (const Vec3 & rhs) - { - this->m_data[0] = rhs.m_data[0]; - this->m_data[1] = rhs.m_data[1]; - this->m_data[2] = rhs.m_data[2]; - } - template - inline void Vec3::operator+=(const Vec3 & rhs) - { - this->m_data[0] += rhs.m_data[0]; - this->m_data[1] += rhs.m_data[1]; - this->m_data[2] += rhs.m_data[2]; - } - template - inline void Vec3::operator-=(const Vec3 & rhs) - { - this->m_data[0] -= rhs.m_data[0]; - this->m_data[1] -= rhs.m_data[1]; - this->m_data[2] -= rhs.m_data[2]; - } - template - inline void Vec3::operator-=(T a) - { - this->m_data[0] -= a; - this->m_data[1] -= a; - this->m_data[2] -= a; - } - template - inline void Vec3::operator+=(T a) - { - this->m_data[0] += a; - this->m_data[1] += a; - this->m_data[2] += a; - } - template - inline void Vec3::operator/=(T a) - { - this->m_data[0] /= a; - this->m_data[1] /= a; - this->m_data[2] /= a; - } - template - inline void Vec3::operator*=(T a) - { - this->m_data[0] *= a; - this->m_data[1] *= a; - this->m_data[2] *= a; - } - template - inline Vec3 Vec3::operator^ (const Vec3 & rhs) const - { - return Vec3(m_data[1] * rhs.m_data[2] - m_data[2] * rhs.m_data[1], - m_data[2] * rhs.m_data[0] - m_data[0] * rhs.m_data[2], - m_data[0] * rhs.m_data[1] - m_data[1] * rhs.m_data[0]); - } - template - inline T Vec3::operator*(const Vec3 & rhs) const - { - return (m_data[0] * rhs.m_data[0] + m_data[1] * rhs.m_data[1] + m_data[2] * rhs.m_data[2]); - } - template - inline Vec3 Vec3::operator+(const Vec3 & rhs) const - { - return Vec3(m_data[0] + rhs.m_data[0],m_data[1] + rhs.m_data[1],m_data[2] + rhs.m_data[2]); - } - template - inline Vec3 Vec3::operator-(const Vec3 & rhs) const - { - return Vec3(m_data[0] - rhs.m_data[0],m_data[1] - rhs.m_data[1],m_data[2] - rhs.m_data[2]) ; - } - template - inline Vec3 Vec3::operator-() const - { - return Vec3(-m_data[0],-m_data[1],-m_data[2]) ; - } - - template - inline Vec3 Vec3::operator*(T rhs) const - { - return Vec3(rhs * this->m_data[0], rhs * this->m_data[1], rhs * this->m_data[2]); - } - template - inline Vec3 Vec3::operator/ (T rhs) const - { - return Vec3(m_data[0] / rhs, m_data[1] / rhs, m_data[2] / rhs); - } - template - inline Vec3::Vec3(T a) - { - m_data[0] = m_data[1] = m_data[2] = a; - } - template - inline Vec3::Vec3(T x, T y, T z) - { - m_data[0] = x; - m_data[1] = y; - m_data[2] = z; - } - template - inline Vec3::Vec3(const Vec3 & rhs) - { - m_data[0] = rhs.m_data[0]; - m_data[1] = rhs.m_data[1]; - m_data[2] = rhs.m_data[2]; - } - template - inline Vec3::~Vec3(void){}; - - template - inline Vec3::Vec3() {} - - template - inline const bool Colinear(const Vec3 & a, const Vec3 & b, const Vec3 & c) - { - return ((c.Z() - a.Z()) * (b.Y() - a.Y()) - (b.Z() - a.Z()) * (c.Y() - a.Y()) == 0.0 /*EPS*/) && - ((b.Z() - a.Z()) * (c.X() - a.X()) - (b.X() - a.X()) * (c.Z() - a.Z()) == 0.0 /*EPS*/) && - ((b.X() - a.X()) * (c.Y() - a.Y()) - (b.Y() - a.Y()) * (c.X() - a.X()) == 0.0 /*EPS*/); - } - - template - inline const T ComputeVolume4(const Vec3 & a, const Vec3 & b, const Vec3 & c, const Vec3 & d) - { - return (a-d) * ((b-d) ^ (c-d)); - } - - template - inline bool Vec3::operator<(const Vec3 & rhs) const - { - if (X() == rhs[0]) - { - if (Y() == rhs[1]) - { - return (Z() - inline bool Vec3::operator>(const Vec3 & rhs) const - { - if (X() == rhs[0]) - { - if (Y() == rhs[1]) - { - return (Z()>rhs[2]); - } - return (Y()>rhs[1]); - } - return (X()>rhs[0]); - } - template - inline Vec2 operator*(T lhs, const Vec2 & rhs) - { - return Vec2(lhs * rhs.X(), lhs * rhs.Y()); - } - template - inline T & Vec2::X() - { - return m_data[0]; - } - template - inline T & Vec2::Y() - { - return m_data[1]; - } - template - inline const T & Vec2::X() const - { - return m_data[0]; - } - template - inline const T & Vec2::Y() const - { - return m_data[1]; - } - template - inline void Vec2::Normalize() - { - T n = sqrt(m_data[0]*m_data[0]+m_data[1]*m_data[1]); - if (n != 0.0) (*this) /= n; - } - template - inline T Vec2::GetNorm() const - { - return sqrt(m_data[0]*m_data[0]+m_data[1]*m_data[1]); - } - template - inline void Vec2::operator= (const Vec2 & rhs) - { - this->m_data[0] = rhs.m_data[0]; - this->m_data[1] = rhs.m_data[1]; - } - template - inline void Vec2::operator+=(const Vec2 & rhs) - { - this->m_data[0] += rhs.m_data[0]; - this->m_data[1] += rhs.m_data[1]; - } - template - inline void Vec2::operator-=(const Vec2 & rhs) - { - this->m_data[0] -= rhs.m_data[0]; - this->m_data[1] -= rhs.m_data[1]; - } - template - inline void Vec2::operator-=(T a) - { - this->m_data[0] -= a; - this->m_data[1] -= a; - } - template - inline void Vec2::operator+=(T a) - { - this->m_data[0] += a; - this->m_data[1] += a; - } - template - inline void Vec2::operator/=(T a) - { - this->m_data[0] /= a; - this->m_data[1] /= a; - } - template - inline void Vec2::operator*=(T a) - { - this->m_data[0] *= a; - this->m_data[1] *= a; - } - template - inline T Vec2::operator^ (const Vec2 & rhs) const - { - return m_data[0] * rhs.m_data[1] - m_data[1] * rhs.m_data[0]; - } - template - inline T Vec2::operator*(const Vec2 & rhs) const - { - return (m_data[0] * rhs.m_data[0] + m_data[1] * rhs.m_data[1]); - } - template - inline Vec2 Vec2::operator+(const Vec2 & rhs) const - { - return Vec2(m_data[0] + rhs.m_data[0],m_data[1] + rhs.m_data[1]); - } - template - inline Vec2 Vec2::operator-(const Vec2 & rhs) const - { - return Vec2(m_data[0] - rhs.m_data[0],m_data[1] - rhs.m_data[1]); - } - template - inline Vec2 Vec2::operator-() const - { - return Vec2(-m_data[0],-m_data[1]) ; - } - - template - inline Vec2 Vec2::operator*(T rhs) const - { - return Vec2(rhs * this->m_data[0], rhs * this->m_data[1]); - } - template - inline Vec2 Vec2::operator/ (T rhs) const - { - return Vec2(m_data[0] / rhs, m_data[1] / rhs); - } - template - inline Vec2::Vec2(T a) - { - m_data[0] = m_data[1] = a; - } - template - inline Vec2::Vec2(T x, T y) - { - m_data[0] = x; - m_data[1] = y; - } - template - inline Vec2::Vec2(const Vec2 & rhs) - { - m_data[0] = rhs.m_data[0]; - m_data[1] = rhs.m_data[1]; - } - template - inline Vec2::~Vec2(void){}; - - template - inline Vec2::Vec2() {} - - /* - InsideTriangle decides if a point P is Inside of the triangle - defined by A, B, C. - */ - template - inline const bool InsideTriangle(const Vec2 & a, const Vec2 & b, const Vec2 & c, const Vec2 & p) - { - T ax, ay, bx, by, cx, cy, apx, apy, bpx, bpy, cpx, cpy; - T cCROSSap, bCROSScp, aCROSSbp; - ax = c.X() - b.X(); ay = c.Y() - b.Y(); - bx = a.X() - c.X(); by = a.Y() - c.Y(); - cx = b.X() - a.X(); cy = b.Y() - a.Y(); - apx= p.X() - a.X(); apy= p.Y() - a.Y(); - bpx= p.X() - b.X(); bpy= p.Y() - b.Y(); - cpx= p.X() - c.X(); cpy= p.Y() - c.Y(); - aCROSSbp = ax*bpy - ay*bpx; - cCROSSap = cx*apy - cy*apx; - bCROSScp = bx*cpy - by*cpx; - return ((aCROSSbp >= 0.0) && (bCROSScp >= 0.0) && (cCROSSap >= 0.0)); - } -} -#endif //VHACD_VECTOR_INL \ No newline at end of file diff --git a/extern/bullet/src/Extras/VHACD/inc/vhacdVolume.h b/extern/bullet/src/Extras/VHACD/inc/vhacdVolume.h deleted file mode 100644 index 31377aa6c90c..000000000000 --- a/extern/bullet/src/Extras/VHACD/inc/vhacdVolume.h +++ /dev/null @@ -1,419 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) - All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#pragma once -#ifndef VHACD_VOLUME_H -#define VHACD_VOLUME_H -#include "vhacdMesh.h" -#include "vhacdVector.h" -#include - -namespace VHACD { - -enum VOXEL_VALUE { - PRIMITIVE_UNDEFINED = 0, - PRIMITIVE_OUTSIDE_SURFACE = 1, - PRIMITIVE_INSIDE_SURFACE = 2, - PRIMITIVE_ON_SURFACE = 3 -}; - -struct Voxel { -public: - short m_coord[3]; - short m_data; -}; - -class PrimitiveSet { -public: - virtual ~PrimitiveSet(){}; - virtual PrimitiveSet* Create() const = 0; - virtual const size_t GetNPrimitives() const = 0; - virtual const size_t GetNPrimitivesOnSurf() const = 0; - virtual const size_t GetNPrimitivesInsideSurf() const = 0; - virtual const double GetEigenValue(AXIS axis) const = 0; - virtual const double ComputeMaxVolumeError() const = 0; - virtual const double ComputeVolume() const = 0; - virtual void Clip(const Plane& plane, PrimitiveSet* const positivePart, - PrimitiveSet* const negativePart) const = 0; - virtual void Intersect(const Plane& plane, SArray >* const positivePts, - SArray >* const negativePts, const size_t sampling) const = 0; - virtual void ComputeExteriorPoints(const Plane& plane, const Mesh& mesh, - SArray >* const exteriorPts) const = 0; - virtual void ComputeClippedVolumes(const Plane& plane, double& positiveVolume, - double& negativeVolume) const = 0; - virtual void SelectOnSurface(PrimitiveSet* const onSurfP) const = 0; - virtual void ComputeConvexHull(Mesh& meshCH, const size_t sampling = 1) const = 0; - virtual void ComputeBB() = 0; - virtual void ComputePrincipalAxes() = 0; - virtual void AlignToPrincipalAxes() = 0; - virtual void RevertAlignToPrincipalAxes() = 0; - virtual void Convert(Mesh& mesh, const VOXEL_VALUE value) const = 0; - const Mesh& GetConvexHull() const { return m_convexHull; }; - Mesh& GetConvexHull() { return m_convexHull; }; -private: - Mesh m_convexHull; -}; - -//! -class VoxelSet : public PrimitiveSet { - friend class Volume; - -public: - //! Destructor. - ~VoxelSet(void); - //! Constructor. - VoxelSet(); - - const size_t GetNPrimitives() const { return m_voxels.Size(); } - const size_t GetNPrimitivesOnSurf() const { return m_numVoxelsOnSurface; } - const size_t GetNPrimitivesInsideSurf() const { return m_numVoxelsInsideSurface; } - const double GetEigenValue(AXIS axis) const { return m_D[axis][axis]; } - const double ComputeVolume() const { return m_unitVolume * m_voxels.Size(); } - const double ComputeMaxVolumeError() const { return m_unitVolume * m_numVoxelsOnSurface; } - const Vec3& GetMinBBVoxels() const { return m_minBBVoxels; } - const Vec3& GetMaxBBVoxels() const { return m_maxBBVoxels; } - const Vec3& GetMinBB() const { return m_minBB; } - const double& GetScale() const { return m_scale; } - const double& GetUnitVolume() const { return m_unitVolume; } - Vec3 GetPoint(Vec3 voxel) const - { - return Vec3(voxel[0] * m_scale + m_minBB[0], - voxel[1] * m_scale + m_minBB[1], - voxel[2] * m_scale + m_minBB[2]); - } - Vec3 GetPoint(const Voxel& voxel) const - { - return Vec3(voxel.m_coord[0] * m_scale + m_minBB[0], - voxel.m_coord[1] * m_scale + m_minBB[1], - voxel.m_coord[2] * m_scale + m_minBB[2]); - } - Vec3 GetPoint(Vec3 voxel) const - { - return Vec3(voxel[0] * m_scale + m_minBB[0], - voxel[1] * m_scale + m_minBB[1], - voxel[2] * m_scale + m_minBB[2]); - } - void GetPoints(const Voxel& voxel, Vec3* const pts) const; - void ComputeConvexHull(Mesh& meshCH, const size_t sampling = 1) const; - void Clip(const Plane& plane, PrimitiveSet* const positivePart, PrimitiveSet* const negativePart) const; - void Intersect(const Plane& plane, SArray >* const positivePts, - SArray >* const negativePts, const size_t sampling) const; - void ComputeExteriorPoints(const Plane& plane, const Mesh& mesh, - SArray >* const exteriorPts) const; - void ComputeClippedVolumes(const Plane& plane, double& positiveVolume, double& negativeVolume) const; - void SelectOnSurface(PrimitiveSet* const onSurfP) const; - void ComputeBB(); - void Convert(Mesh& mesh, const VOXEL_VALUE value) const; - void ComputePrincipalAxes(); - PrimitiveSet* Create() const - { - return new VoxelSet(); - } - void AlignToPrincipalAxes(){}; - void RevertAlignToPrincipalAxes(){}; - Voxel* const GetVoxels() { return m_voxels.Data(); } - const Voxel* const GetVoxels() const { return m_voxels.Data(); } - -private: - size_t m_numVoxelsOnSurface; - size_t m_numVoxelsInsideSurface; - Vec3 m_minBB; - double m_scale; - SArray m_voxels; - double m_unitVolume; - Vec3 m_minBBPts; - Vec3 m_maxBBPts; - Vec3 m_minBBVoxels; - Vec3 m_maxBBVoxels; - Vec3 m_barycenter; - double m_Q[3][3]; - double m_D[3][3]; - Vec3 m_barycenterPCA; -}; - -struct Tetrahedron { -public: - Vec3 m_pts[4]; - unsigned char m_data; -}; - -//! -class TetrahedronSet : public PrimitiveSet { - friend class Volume; - -public: - //! Destructor. - ~TetrahedronSet(void); - //! Constructor. - TetrahedronSet(); - - const size_t GetNPrimitives() const { return m_tetrahedra.Size(); } - const size_t GetNPrimitivesOnSurf() const { return m_numTetrahedraOnSurface; } - const size_t GetNPrimitivesInsideSurf() const { return m_numTetrahedraInsideSurface; } - const Vec3& GetMinBB() const { return m_minBB; } - const Vec3& GetMaxBB() const { return m_maxBB; } - const Vec3& GetBarycenter() const { return m_barycenter; } - const double GetEigenValue(AXIS axis) const { return m_D[axis][axis]; } - const double GetSacle() const { return m_scale; } - const double ComputeVolume() const; - const double ComputeMaxVolumeError() const; - void ComputeConvexHull(Mesh& meshCH, const size_t sampling = 1) const; - void ComputePrincipalAxes(); - void AlignToPrincipalAxes(); - void RevertAlignToPrincipalAxes(); - void Clip(const Plane& plane, PrimitiveSet* const positivePart, PrimitiveSet* const negativePart) const; - void Intersect(const Plane& plane, SArray >* const positivePts, - SArray >* const negativePts, const size_t sampling) const; - void ComputeExteriorPoints(const Plane& plane, const Mesh& mesh, - SArray >* const exteriorPts) const; - void ComputeClippedVolumes(const Plane& plane, double& positiveVolume, double& negativeVolume) const; - void SelectOnSurface(PrimitiveSet* const onSurfP) const; - void ComputeBB(); - void Convert(Mesh& mesh, const VOXEL_VALUE value) const; - inline bool Add(Tetrahedron& tetrahedron); - PrimitiveSet* Create() const - { - return new TetrahedronSet(); - } - static const double EPS; - -private: - void AddClippedTetrahedra(const Vec3 (&pts)[10], const int nPts); - - size_t m_numTetrahedraOnSurface; - size_t m_numTetrahedraInsideSurface; - double m_scale; - Vec3 m_minBB; - Vec3 m_maxBB; - Vec3 m_barycenter; - SArray m_tetrahedra; - double m_Q[3][3]; - double m_D[3][3]; -}; - -//! -class Volume { -public: - //! Destructor. - ~Volume(void); - - //! Constructor. - Volume(); - - //! Voxelize - template - void Voxelize(const T* const points, const unsigned int stridePoints, const unsigned int nPoints, - const int* const triangles, const unsigned int strideTriangles, const unsigned int nTriangles, - const size_t dim, const Vec3& barycenter, const double (&rot)[3][3]); - unsigned char& GetVoxel(const size_t i, const size_t j, const size_t k) - { - assert(i < m_dim[0] || i >= 0); - assert(j < m_dim[0] || j >= 0); - assert(k < m_dim[0] || k >= 0); - return m_data[i + j * m_dim[0] + k * m_dim[0] * m_dim[1]]; - } - const unsigned char& GetVoxel(const size_t i, const size_t j, const size_t k) const - { - assert(i < m_dim[0] || i >= 0); - assert(j < m_dim[0] || j >= 0); - assert(k < m_dim[0] || k >= 0); - return m_data[i + j * m_dim[0] + k * m_dim[0] * m_dim[1]]; - } - const size_t GetNPrimitivesOnSurf() const { return m_numVoxelsOnSurface; } - const size_t GetNPrimitivesInsideSurf() const { return m_numVoxelsInsideSurface; } - void Convert(Mesh& mesh, const VOXEL_VALUE value) const; - void Convert(VoxelSet& vset) const; - void Convert(TetrahedronSet& tset) const; - void AlignToPrincipalAxes(double (&rot)[3][3]) const; - -private: - void FillOutsideSurface(const size_t i0, const size_t j0, const size_t k0, const size_t i1, - const size_t j1, const size_t k1); - void FillInsideSurface(); - template - void ComputeBB(const T* const points, const unsigned int stridePoints, const unsigned int nPoints, - const Vec3& barycenter, const double (&rot)[3][3]); - void Allocate(); - void Free(); - - Vec3 m_minBB; - Vec3 m_maxBB; - double m_scale; - size_t m_dim[3]; //>! dim - size_t m_numVoxelsOnSurface; - size_t m_numVoxelsInsideSurface; - size_t m_numVoxelsOutsideSurface; - unsigned char* m_data; -}; -int TriBoxOverlap(const Vec3& boxcenter, const Vec3& boxhalfsize, const Vec3& triver0, - const Vec3& triver1, const Vec3& triver2); -template -inline void ComputeAlignedPoint(const T* const points, const unsigned int idx, const Vec3& barycenter, - const double (&rot)[3][3], Vec3& pt){}; -template <> -inline void ComputeAlignedPoint(const float* const points, const unsigned int idx, const Vec3& barycenter, const double (&rot)[3][3], Vec3& pt) -{ - double x = points[idx + 0] - barycenter[0]; - double y = points[idx + 1] - barycenter[1]; - double z = points[idx + 2] - barycenter[2]; - pt[0] = rot[0][0] * x + rot[1][0] * y + rot[2][0] * z; - pt[1] = rot[0][1] * x + rot[1][1] * y + rot[2][1] * z; - pt[2] = rot[0][2] * x + rot[1][2] * y + rot[2][2] * z; -} -template <> -inline void ComputeAlignedPoint(const double* const points, const unsigned int idx, const Vec3& barycenter, const double (&rot)[3][3], Vec3& pt) -{ - double x = points[idx + 0] - barycenter[0]; - double y = points[idx + 1] - barycenter[1]; - double z = points[idx + 2] - barycenter[2]; - pt[0] = rot[0][0] * x + rot[1][0] * y + rot[2][0] * z; - pt[1] = rot[0][1] * x + rot[1][1] * y + rot[2][1] * z; - pt[2] = rot[0][2] * x + rot[1][2] * y + rot[2][2] * z; -} -template -void Volume::ComputeBB(const T* const points, const unsigned int stridePoints, const unsigned int nPoints, - const Vec3& barycenter, const double (&rot)[3][3]) -{ - Vec3 pt; - ComputeAlignedPoint(points, 0, barycenter, rot, pt); - m_maxBB = pt; - m_minBB = pt; - for (unsigned int v = 1; v < nPoints; ++v) { - ComputeAlignedPoint(points, v * stridePoints, barycenter, rot, pt); - for (int i = 0; i < 3; ++i) { - if (pt[i] < m_minBB[i]) - m_minBB[i] = pt[i]; - else if (pt[i] > m_maxBB[i]) - m_maxBB[i] = pt[i]; - } - } -} -template -void Volume::Voxelize(const T* const points, const unsigned int stridePoints, const unsigned int nPoints, - const int* const triangles, const unsigned int strideTriangles, const unsigned int nTriangles, - const size_t dim, const Vec3& barycenter, const double (&rot)[3][3]) -{ - if (nPoints == 0) { - return; - } - ComputeBB(points, stridePoints, nPoints, barycenter, rot); - - double d[3] = { m_maxBB[0] - m_minBB[0], m_maxBB[1] - m_minBB[1], m_maxBB[2] - m_minBB[2] }; - double r; - if (d[0] > d[1] && d[0] > d[2]) { - r = d[0]; - m_dim[0] = dim; - m_dim[1] = 2 + static_cast(dim * d[1] / d[0]); - m_dim[2] = 2 + static_cast(dim * d[2] / d[0]); - } - else if (d[1] > d[0] && d[1] > d[2]) { - r = d[1]; - m_dim[1] = dim; - m_dim[0] = 2 + static_cast(dim * d[0] / d[1]); - m_dim[2] = 2 + static_cast(dim * d[2] / d[1]); - } - else { - r = d[2]; - m_dim[2] = dim; - m_dim[0] = 2 + static_cast(dim * d[0] / d[2]); - m_dim[1] = 2 + static_cast(dim * d[1] / d[2]); - } - - m_scale = r / (dim - 1); - double invScale = (dim - 1) / r; - - Allocate(); - m_numVoxelsOnSurface = 0; - m_numVoxelsInsideSurface = 0; - m_numVoxelsOutsideSurface = 0; - - Vec3 p[3]; - size_t i, j, k; - size_t i0, j0, k0; - size_t i1, j1, k1; - Vec3 boxcenter; - Vec3 pt; - const Vec3 boxhalfsize(0.5, 0.5, 0.5); - for (size_t t = 0, ti = 0; t < nTriangles; ++t, ti += strideTriangles) { - Vec3 tri(triangles[ti + 0], - triangles[ti + 1], - triangles[ti + 2]); - for (int c = 0; c < 3; ++c) { - ComputeAlignedPoint(points, tri[c] * stridePoints, barycenter, rot, pt); - p[c][0] = (pt[0] - m_minBB[0]) * invScale; - p[c][1] = (pt[1] - m_minBB[1]) * invScale; - p[c][2] = (pt[2] - m_minBB[2]) * invScale; - i = static_cast(p[c][0] + 0.5); - j = static_cast(p[c][1] + 0.5); - k = static_cast(p[c][2] + 0.5); - assert(i < m_dim[0] && i >= 0 && j < m_dim[1] && j >= 0 && k < m_dim[2] && k >= 0); - - if (c == 0) { - i0 = i1 = i; - j0 = j1 = j; - k0 = k1 = k; - } - else { - if (i < i0) - i0 = i; - if (j < j0) - j0 = j; - if (k < k0) - k0 = k; - if (i > i1) - i1 = i; - if (j > j1) - j1 = j; - if (k > k1) - k1 = k; - } - } - if (i0 > 0) - --i0; - if (j0 > 0) - --j0; - if (k0 > 0) - --k0; - if (i1 < m_dim[0]) - ++i1; - if (j1 < m_dim[1]) - ++j1; - if (k1 < m_dim[2]) - ++k1; - for (size_t i = i0; i < i1; ++i) { - boxcenter[0] = (double)i; - for (size_t j = j0; j < j1; ++j) { - boxcenter[1] = (double)j; - for (size_t k = k0; k < k1; ++k) { - boxcenter[2] = (double)k; - int res = TriBoxOverlap(boxcenter, boxhalfsize, p[0], p[1], p[2]); - unsigned char& value = GetVoxel(i, j, k); - if (res == 1 && value == PRIMITIVE_UNDEFINED) { - value = PRIMITIVE_ON_SURFACE; - ++m_numVoxelsOnSurface; - } - } - } - } - } - FillOutsideSurface(0, 0, 0, m_dim[0], m_dim[1], 1); - FillOutsideSurface(0, 0, m_dim[2] - 1, m_dim[0], m_dim[1], m_dim[2]); - FillOutsideSurface(0, 0, 0, m_dim[0], 1, m_dim[2]); - FillOutsideSurface(0, m_dim[1] - 1, 0, m_dim[0], m_dim[1], m_dim[2]); - FillOutsideSurface(0, 0, 0, 1, m_dim[1], m_dim[2]); - FillOutsideSurface(m_dim[0] - 1, 0, 0, m_dim[0], m_dim[1], m_dim[2]); - FillInsideSurface(); -} -} -#endif // VHACD_VOLUME_H diff --git a/extern/bullet/src/Extras/VHACD/premake4.lua b/extern/bullet/src/Extras/VHACD/premake4.lua deleted file mode 100644 index f66f160e27cf..000000000000 --- a/extern/bullet/src/Extras/VHACD/premake4.lua +++ /dev/null @@ -1,4 +0,0 @@ - -include "src" -include "test/src" - diff --git a/extern/bullet/src/Extras/VHACD/public/VHACD.h b/extern/bullet/src/Extras/VHACD/public/VHACD.h deleted file mode 100644 index 20f6aacd9fbe..000000000000 --- a/extern/bullet/src/Extras/VHACD/public/VHACD.h +++ /dev/null @@ -1,121 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) - All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#pragma once -#ifndef VHACD_H -#define VHACD_H - -#define VHACD_VERSION_MAJOR 2 -#define VHACD_VERSION_MINOR 2 - -namespace VHACD { -class IVHACD { -public: - class IUserCallback { - public: - virtual ~IUserCallback(){}; - virtual void Update(const double overallProgress, - const double stageProgress, - const double operationProgress, - const char* const stage, - const char* const operation) - = 0; - }; - - class IUserLogger { - public: - virtual ~IUserLogger(){}; - virtual void Log(const char* const msg) = 0; - }; - - class ConvexHull { - public: - double* m_points; - int* m_triangles; - unsigned int m_nPoints; - unsigned int m_nTriangles; - }; - - class Parameters { - public: - Parameters(void) { Init(); } - void Init(void) - { - m_resolution = 1000000; - m_depth = 20; - m_concavity = 0.001; - m_planeDownsampling = 4; - m_convexhullDownsampling = 4; - m_alpha = 0.05; - m_beta = 0.05; - m_gamma = 0.0005; - m_pca = 0; - m_mode = 0; // 0: voxel-based (recommended), 1: tetrahedron-based - m_maxNumVerticesPerCH = 64; - m_minVolumePerCH = 0.0001; - m_callback = 0; - m_logger = 0; - m_convexhullApproximation = true; - m_oclAcceleration = true; - } - double m_concavity; - double m_alpha; - double m_beta; - double m_gamma; - double m_minVolumePerCH; - IUserCallback* m_callback; - IUserLogger* m_logger; - unsigned int m_resolution; - unsigned int m_maxNumVerticesPerCH; - int m_depth; - int m_planeDownsampling; - int m_convexhullDownsampling; - int m_pca; - int m_mode; - int m_convexhullApproximation; - int m_oclAcceleration; - }; - - virtual void Cancel() = 0; - virtual bool Compute(const float* const points, - const unsigned int stridePoints, - const unsigned int countPoints, - const int* const triangles, - const unsigned int strideTriangles, - const unsigned int countTriangles, - const Parameters& params) - = 0; - virtual bool Compute(const double* const points, - const unsigned int stridePoints, - const unsigned int countPoints, - const int* const triangles, - const unsigned int strideTriangles, - const unsigned int countTriangles, - const Parameters& params) - = 0; - virtual unsigned int GetNConvexHulls() const = 0; - virtual void GetConvexHull(const unsigned int index, ConvexHull& ch) const = 0; - virtual void Clean(void) = 0; // release internally allocated memory - virtual void Release(void) = 0; // release IVHACD - virtual bool OCLInit(void* const oclDevice, - IUserLogger* const logger = 0) - = 0; - virtual bool OCLRelease(IUserLogger* const logger = 0) = 0; - -protected: - virtual ~IVHACD(void) {} -}; -IVHACD* CreateVHACD(void); -} -#endif // VHACD_H \ No newline at end of file diff --git a/extern/bullet/src/Extras/VHACD/src/VHACD.cpp b/extern/bullet/src/Extras/VHACD/src/VHACD.cpp deleted file mode 100644 index 3310f6040329..000000000000 --- a/extern/bullet/src/Extras/VHACD/src/VHACD.cpp +++ /dev/null @@ -1,1433 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) - All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ - -#define _CRT_SECURE_NO_WARNINGS - -#include -#include -#include -#include -#include -#if _OPENMP -#include -#endif // _OPENMP - -#include "../public/VHACD.h" -#include "Extras/VHACD/inc/btConvexHullComputer.h" -#include "Extras/VHACD/inc/vhacdICHull.h" -#include "Extras/VHACD/inc/vhacdMesh.h" -#include "Extras/VHACD/inc/vhacdSArray.h" -#include "Extras/VHACD/inc/vhacdTimer.h" -#include "Extras/VHACD/inc/vhacdVHACD.h" -#include "Extras/VHACD/inc/vhacdVector.h" -#include "Extras/VHACD/inc/vhacdVolume.h" - -#define MAX(a, b) (((a) > (b)) ? (a) : (b)) -#define MIN(a, b) (((a) < (b)) ? (a) : (b)) -#define ABS(a) (((a) < 0) ? -(a) : (a)) -#define ZSGN(a) (((a) < 0) ? -1 : (a) > 0 ? 1 : 0) -#define MAX_DOUBLE (1.79769e+308) - -#ifdef USE_SSE -#include - -const int SIMD_WIDTH = 4; -inline int FindMinimumElement(const float* const d, float* const m, const int n) -{ - // Min within vectors - __m128 min_i = _mm_set1_ps(-1.0f); - __m128 min_v = _mm_set1_ps(std::numeric_limits::max()); - for (int i = 0; i <= n - SIMD_WIDTH; i += SIMD_WIDTH) { - const __m128 data = _mm_load_ps(&d[i]); - const __m128 pred = _mm_cmplt_ps(data, min_v); - - min_i = _mm_blendv_ps(min_i, _mm_set1_ps(i), pred); - min_v = _mm_min_ps(data, min_v); - } - - /* Min within vector */ - const __m128 min1 = _mm_shuffle_ps(min_v, min_v, _MM_SHUFFLE(1, 0, 3, 2)); - const __m128 min2 = _mm_min_ps(min_v, min1); - const __m128 min3 = _mm_shuffle_ps(min2, min2, _MM_SHUFFLE(0, 1, 0, 1)); - const __m128 min4 = _mm_min_ps(min2, min3); - float min_d = _mm_cvtss_f32(min4); - - // Min index - const int min_idx = __builtin_ctz(_mm_movemask_ps(_mm_cmpeq_ps(min_v, min4))); - int ret = min_i[min_idx] + min_idx; - - // Trailing elements - for (int i = (n & ~(SIMD_WIDTH - 1)); i < n; ++i) { - if (d[i] < min_d) { - min_d = d[i]; - ret = i; - } - } - - *m = min_d; - return ret; -} - -inline int FindMinimumElement(const float* const d, float* const m, const int begin, const int end) -{ - // Leading elements - int min_i = -1; - float min_d = std::numeric_limits::max(); - const int aligned = (begin & ~(SIMD_WIDTH - 1)) + ((begin & (SIMD_WIDTH - 1)) ? SIMD_WIDTH : 0); - for (int i = begin; i < std::min(end, aligned); ++i) { - if (d[i] < min_d) { - min_d = d[i]; - min_i = i; - } - } - - // Middle and trailing elements - float r_m = std::numeric_limits::max(); - const int n = end - aligned; - const int r_i = (n > 0) ? FindMinimumElement(&d[aligned], &r_m, n) : 0; - - // Pick the lowest - if (r_m < min_d) { - *m = r_m; - return r_i + aligned; - } - else { - *m = min_d; - return min_i; - } -} -#else -inline int FindMinimumElement(const float* const d, float* const m, const int begin, const int end) -{ - int idx = -1; - float min = (std::numeric_limits::max)(); - for (int i = begin; i < end; ++i) { - if (d[i] < min) { - idx = i; - min = d[i]; - } - } - - *m = min; - return idx; -} -#endif - -//#define OCL_SOURCE_FROM_FILE -#ifndef OCL_SOURCE_FROM_FILE -const char* oclProgramSource = "\ -__kernel void ComputePartialVolumes(__global short4 * voxels, \ - const int numVoxels, \ - const float4 plane, \ - const float4 minBB, \ - const float4 scale, \ - __local uint4 * localPartialVolumes, \ - __global uint4 * partialVolumes) \ -{ \ - int localId = get_local_id(0); \ - int groupSize = get_local_size(0); \ - int i0 = get_global_id(0) << 2; \ - float4 voxel; \ - uint4 v; \ - voxel = convert_float4(voxels[i0]); \ - v.s0 = (dot(plane, mad(scale, voxel, minBB)) >= 0.0f) * (i0 < numVoxels);\ - voxel = convert_float4(voxels[i0 + 1]); \ - v.s1 = (dot(plane, mad(scale, voxel, minBB)) >= 0.0f) * (i0 + 1 < numVoxels);\ - voxel = convert_float4(voxels[i0 + 2]); \ - v.s2 = (dot(plane, mad(scale, voxel, minBB)) >= 0.0f) * (i0 + 2 < numVoxels);\ - voxel = convert_float4(voxels[i0 + 3]); \ - v.s3 = (dot(plane, mad(scale, voxel, minBB)) >= 0.0f) * (i0 + 3 < numVoxels);\ - localPartialVolumes[localId] = v; \ - barrier(CLK_LOCAL_MEM_FENCE); \ - for (int i = groupSize >> 1; i > 0; i >>= 1) \ - { \ - if (localId < i) \ - { \ - localPartialVolumes[localId] += localPartialVolumes[localId + i]; \ - } \ - barrier(CLK_LOCAL_MEM_FENCE); \ - } \ - if (localId == 0) \ - { \ - partialVolumes[get_group_id(0)] = localPartialVolumes[0]; \ - } \ -} \ -__kernel void ComputePartialSums(__global uint4 * data, \ - const int dataSize, \ - __local uint4 * partialSums) \ -{ \ - int globalId = get_global_id(0); \ - int localId = get_local_id(0); \ - int groupSize = get_local_size(0); \ - int i; \ - if (globalId < dataSize) \ - { \ - partialSums[localId] = data[globalId]; \ - } \ - else \ - { \ - partialSums[localId] = (0, 0, 0, 0); \ - } \ - barrier(CLK_LOCAL_MEM_FENCE); \ - for (i = groupSize >> 1; i > 0; i >>= 1) \ - { \ - if (localId < i) \ - { \ - partialSums[localId] += partialSums[localId + i]; \ - } \ - barrier(CLK_LOCAL_MEM_FENCE); \ - } \ - if (localId == 0) \ - { \ - data[get_group_id(0)] = partialSums[0]; \ - } \ -}"; -#endif //OCL_SOURCE_FROM_FILE - -namespace VHACD { -IVHACD* CreateVHACD(void) -{ - return new VHACD(); -} -bool VHACD::OCLInit(void* const oclDevice, IUserLogger* const logger) -{ -#ifdef CL_VERSION_1_1 - m_oclDevice = (cl_device_id*)oclDevice; - cl_int error; - m_oclContext = clCreateContext(NULL, 1, m_oclDevice, NULL, NULL, &error); - if (error != CL_SUCCESS) { - if (logger) { - logger->Log("Couldn't create context\n"); - } - return false; - } - -#ifdef OCL_SOURCE_FROM_FILE - std::string cl_files = OPENCL_CL_FILES; -// read kernal from file -#ifdef _WIN32 - std::replace(cl_files.begin(), cl_files.end(), '/', '\\'); -#endif // _WIN32 - - FILE* program_handle = fopen(cl_files.c_str(), "rb"); - fseek(program_handle, 0, SEEK_END); - size_t program_size = ftell(program_handle); - rewind(program_handle); - char* program_buffer = new char[program_size + 1]; - program_buffer[program_size] = '\0'; - fread(program_buffer, sizeof(char), program_size, program_handle); - fclose(program_handle); - // create program - m_oclProgram = clCreateProgramWithSource(m_oclContext, 1, (const char**)&program_buffer, &program_size, &error); - delete[] program_buffer; -#else - size_t program_size = strlen(oclProgramSource); - m_oclProgram = clCreateProgramWithSource(m_oclContext, 1, (const char**)&oclProgramSource, &program_size, &error); -#endif - if (error != CL_SUCCESS) { - if (logger) { - logger->Log("Couldn't create program\n"); - } - return false; - } - - /* Build program */ - error = clBuildProgram(m_oclProgram, 1, m_oclDevice, "-cl-denorms-are-zero", NULL, NULL); - if (error != CL_SUCCESS) { - size_t log_size; - /* Find Size of log and print to std output */ - clGetProgramBuildInfo(m_oclProgram, *m_oclDevice, CL_PROGRAM_BUILD_LOG, 0, NULL, &log_size); - char* program_log = new char[log_size + 2]; - program_log[log_size] = '\n'; - program_log[log_size + 1] = '\0'; - clGetProgramBuildInfo(m_oclProgram, *m_oclDevice, CL_PROGRAM_BUILD_LOG, log_size + 1, program_log, NULL); - if (logger) { - logger->Log("Couldn't build program\n"); - logger->Log(program_log); - } - delete[] program_log; - return false; - } - - delete[] m_oclQueue; - delete[] m_oclKernelComputePartialVolumes; - delete[] m_oclKernelComputeSum; - m_oclQueue = new cl_command_queue[m_ompNumProcessors]; - m_oclKernelComputePartialVolumes = new cl_kernel[m_ompNumProcessors]; - m_oclKernelComputeSum = new cl_kernel[m_ompNumProcessors]; - - const char nameKernelComputePartialVolumes[] = "ComputePartialVolumes"; - const char nameKernelComputeSum[] = "ComputePartialSums"; - for (int k = 0; k < m_ompNumProcessors; ++k) { - m_oclKernelComputePartialVolumes[k] = clCreateKernel(m_oclProgram, nameKernelComputePartialVolumes, &error); - if (error != CL_SUCCESS) { - if (logger) { - logger->Log("Couldn't create kernel\n"); - } - return false; - } - m_oclKernelComputeSum[k] = clCreateKernel(m_oclProgram, nameKernelComputeSum, &error); - if (error != CL_SUCCESS) { - if (logger) { - logger->Log("Couldn't create kernel\n"); - } - return false; - } - } - - error = clGetKernelWorkGroupInfo(m_oclKernelComputePartialVolumes[0], - *m_oclDevice, - CL_KERNEL_WORK_GROUP_SIZE, - sizeof(size_t), - &m_oclWorkGroupSize, - NULL); - size_t workGroupSize = 0; - error = clGetKernelWorkGroupInfo(m_oclKernelComputeSum[0], - *m_oclDevice, - CL_KERNEL_WORK_GROUP_SIZE, - sizeof(size_t), - &workGroupSize, - NULL); - if (error != CL_SUCCESS) { - if (logger) { - logger->Log("Couldn't query work group info\n"); - } - return false; - } - - if (workGroupSize < m_oclWorkGroupSize) { - m_oclWorkGroupSize = workGroupSize; - } - - for (int k = 0; k < m_ompNumProcessors; ++k) { - m_oclQueue[k] = clCreateCommandQueue(m_oclContext, *m_oclDevice, 0 /*CL_QUEUE_PROFILING_ENABLE*/, &error); - if (error != CL_SUCCESS) { - if (logger) { - logger->Log("Couldn't create queue\n"); - } - return false; - } - } - return true; -#else //CL_VERSION_1_1 - return false; -#endif //CL_VERSION_1_1 -} -bool VHACD::OCLRelease(IUserLogger* const logger) -{ -#ifdef CL_VERSION_1_1 - cl_int error; - if (m_oclKernelComputePartialVolumes) { - for (int k = 0; k < m_ompNumProcessors; ++k) { - error = clReleaseKernel(m_oclKernelComputePartialVolumes[k]); - if (error != CL_SUCCESS) { - if (logger) { - logger->Log("Couldn't release kernal\n"); - } - return false; - } - } - delete[] m_oclKernelComputePartialVolumes; - } - if (m_oclKernelComputeSum) { - for (int k = 0; k < m_ompNumProcessors; ++k) { - error = clReleaseKernel(m_oclKernelComputeSum[k]); - if (error != CL_SUCCESS) { - if (logger) { - logger->Log("Couldn't release kernal\n"); - } - return false; - } - } - delete[] m_oclKernelComputeSum; - } - if (m_oclQueue) { - for (int k = 0; k < m_ompNumProcessors; ++k) { - error = clReleaseCommandQueue(m_oclQueue[k]); - if (error != CL_SUCCESS) { - if (logger) { - logger->Log("Couldn't release queue\n"); - } - return false; - } - } - delete[] m_oclQueue; - } - error = clReleaseProgram(m_oclProgram); - if (error != CL_SUCCESS) { - if (logger) { - logger->Log("Couldn't release program\n"); - } - return false; - } - error = clReleaseContext(m_oclContext); - if (error != CL_SUCCESS) { - if (logger) { - logger->Log("Couldn't release context\n"); - } - return false; - } - - return true; -#else //CL_VERSION_1_1 - return false; -#endif //CL_VERSION_1_1 -} -void VHACD::ComputePrimitiveSet(const Parameters& params) -{ - if (GetCancel()) { - return; - } - m_timer.Tic(); - - m_stage = "Compute primitive set"; - m_operation = "Convert volume to pset"; - - std::ostringstream msg; - if (params.m_logger) { - msg << "+ " << m_stage << std::endl; - params.m_logger->Log(msg.str().c_str()); - } - - Update(0.0, 0.0, params); - if (params.m_mode == 0) { - VoxelSet* vset = new VoxelSet; - m_volume->Convert(*vset); - m_pset = vset; - } - else { - TetrahedronSet* tset = new TetrahedronSet; - m_volume->Convert(*tset); - m_pset = tset; - } - - delete m_volume; - m_volume = 0; - - if (params.m_logger) { - msg.str(""); - msg << "\t # primitives " << m_pset->GetNPrimitives() << std::endl; - msg << "\t # inside surface " << m_pset->GetNPrimitivesInsideSurf() << std::endl; - msg << "\t # on surface " << m_pset->GetNPrimitivesOnSurf() << std::endl; - params.m_logger->Log(msg.str().c_str()); - } - - m_overallProgress = 15.0; - Update(100.0, 100.0, params); - m_timer.Toc(); - if (params.m_logger) { - msg.str(""); - msg << "\t time " << m_timer.GetElapsedTime() / 1000.0 << "s" << std::endl; - params.m_logger->Log(msg.str().c_str()); - } -} -bool VHACD::Compute(const double* const points, const unsigned int stridePoints, const unsigned int nPoints, - const int* const triangles, const unsigned int strideTriangles, const unsigned int nTriangles, const Parameters& params) -{ - return ComputeACD(points, stridePoints, nPoints, triangles, strideTriangles, nTriangles, params); -} -bool VHACD::Compute(const float* const points, const unsigned int stridePoints, const unsigned int nPoints, - const int* const triangles, const unsigned int strideTriangles, const unsigned int nTriangles, const Parameters& params) -{ - return ComputeACD(points, stridePoints, nPoints, triangles, strideTriangles, nTriangles, params); -} -double ComputePreferredCuttingDirection(const PrimitiveSet* const tset, Vec3& dir) -{ - double ex = tset->GetEigenValue(AXIS_X); - double ey = tset->GetEigenValue(AXIS_Y); - double ez = tset->GetEigenValue(AXIS_Z); - double vx = (ey - ez) * (ey - ez); - double vy = (ex - ez) * (ex - ez); - double vz = (ex - ey) * (ex - ey); - if (vx < vy && vx < vz) { - double e = ey * ey + ez * ez; - dir[0] = 1.0; - dir[1] = 0.0; - dir[2] = 0.0; - return (e == 0.0) ? 0.0 : 1.0 - vx / e; - } - else if (vy < vx && vy < vz) { - double e = ex * ex + ez * ez; - dir[0] = 0.0; - dir[1] = 1.0; - dir[2] = 0.0; - return (e == 0.0) ? 0.0 : 1.0 - vy / e; - } - else { - double e = ex * ex + ey * ey; - dir[0] = 0.0; - dir[1] = 0.0; - dir[2] = 1.0; - return (e == 0.0) ? 0.0 : 1.0 - vz / e; - } -} -void ComputeAxesAlignedClippingPlanes(const VoxelSet& vset, const short downsampling, SArray& planes) -{ - const Vec3 minV = vset.GetMinBBVoxels(); - const Vec3 maxV = vset.GetMaxBBVoxels(); - Vec3 pt; - Plane plane; - const short i0 = minV[0]; - const short i1 = maxV[0]; - plane.m_a = 1.0; - plane.m_b = 0.0; - plane.m_c = 0.0; - plane.m_axis = AXIS_X; - for (short i = i0; i <= i1; i += downsampling) { - pt = vset.GetPoint(Vec3(i + 0.5, 0.0, 0.0)); - plane.m_d = -pt[0]; - plane.m_index = i; - planes.PushBack(plane); - } - const short j0 = minV[1]; - const short j1 = maxV[1]; - plane.m_a = 0.0; - plane.m_b = 1.0; - plane.m_c = 0.0; - plane.m_axis = AXIS_Y; - for (short j = j0; j <= j1; j += downsampling) { - pt = vset.GetPoint(Vec3(0.0, j + 0.5, 0.0)); - plane.m_d = -pt[1]; - plane.m_index = j; - planes.PushBack(plane); - } - const short k0 = minV[2]; - const short k1 = maxV[2]; - plane.m_a = 0.0; - plane.m_b = 0.0; - plane.m_c = 1.0; - plane.m_axis = AXIS_Z; - for (short k = k0; k <= k1; k += downsampling) { - pt = vset.GetPoint(Vec3(0.0, 0.0, k + 0.5)); - plane.m_d = -pt[2]; - plane.m_index = k; - planes.PushBack(plane); - } -} -void ComputeAxesAlignedClippingPlanes(const TetrahedronSet& tset, const short downsampling, SArray& planes) -{ - const Vec3 minV = tset.GetMinBB(); - const Vec3 maxV = tset.GetMaxBB(); - const double scale = tset.GetSacle(); - const short i0 = 0; - const short j0 = 0; - const short k0 = 0; - const short i1 = static_cast((maxV[0] - minV[0]) / scale + 0.5); - const short j1 = static_cast((maxV[1] - minV[1]) / scale + 0.5); - const short k1 = static_cast((maxV[2] - minV[2]) / scale + 0.5); - - Plane plane; - plane.m_a = 1.0; - plane.m_b = 0.0; - plane.m_c = 0.0; - plane.m_axis = AXIS_X; - for (short i = i0; i <= i1; i += downsampling) { - double x = minV[0] + scale * i; - plane.m_d = -x; - plane.m_index = i; - planes.PushBack(plane); - } - plane.m_a = 0.0; - plane.m_b = 1.0; - plane.m_c = 0.0; - plane.m_axis = AXIS_Y; - for (short j = j0; j <= j1; j += downsampling) { - double y = minV[1] + scale * j; - plane.m_d = -y; - plane.m_index = j; - planes.PushBack(plane); - } - plane.m_a = 0.0; - plane.m_b = 0.0; - plane.m_c = 1.0; - plane.m_axis = AXIS_Z; - for (short k = k0; k <= k1; k += downsampling) { - double z = minV[2] + scale * k; - plane.m_d = -z; - plane.m_index = k; - planes.PushBack(plane); - } -} -void RefineAxesAlignedClippingPlanes(const VoxelSet& vset, const Plane& bestPlane, const short downsampling, - SArray& planes) -{ - const Vec3 minV = vset.GetMinBBVoxels(); - const Vec3 maxV = vset.GetMaxBBVoxels(); - Vec3 pt; - Plane plane; - - if (bestPlane.m_axis == AXIS_X) { - const short i0 = MAX(minV[0], bestPlane.m_index - downsampling); - const short i1 = MIN(maxV[0], bestPlane.m_index + downsampling); - plane.m_a = 1.0; - plane.m_b = 0.0; - plane.m_c = 0.0; - plane.m_axis = AXIS_X; - for (short i = i0; i <= i1; ++i) { - pt = vset.GetPoint(Vec3(i + 0.5, 0.0, 0.0)); - plane.m_d = -pt[0]; - plane.m_index = i; - planes.PushBack(plane); - } - } - else if (bestPlane.m_axis == AXIS_Y) { - const short j0 = MAX(minV[1], bestPlane.m_index - downsampling); - const short j1 = MIN(maxV[1], bestPlane.m_index + downsampling); - plane.m_a = 0.0; - plane.m_b = 1.0; - plane.m_c = 0.0; - plane.m_axis = AXIS_Y; - for (short j = j0; j <= j1; ++j) { - pt = vset.GetPoint(Vec3(0.0, j + 0.5, 0.0)); - plane.m_d = -pt[1]; - plane.m_index = j; - planes.PushBack(plane); - } - } - else { - const short k0 = MAX(minV[2], bestPlane.m_index - downsampling); - const short k1 = MIN(maxV[2], bestPlane.m_index + downsampling); - plane.m_a = 0.0; - plane.m_b = 0.0; - plane.m_c = 1.0; - plane.m_axis = AXIS_Z; - for (short k = k0; k <= k1; ++k) { - pt = vset.GetPoint(Vec3(0.0, 0.0, k + 0.5)); - plane.m_d = -pt[2]; - plane.m_index = k; - planes.PushBack(plane); - } - } -} -void RefineAxesAlignedClippingPlanes(const TetrahedronSet& tset, const Plane& bestPlane, const short downsampling, - SArray& planes) -{ - const Vec3 minV = tset.GetMinBB(); - const Vec3 maxV = tset.GetMaxBB(); - const double scale = tset.GetSacle(); - Plane plane; - - if (bestPlane.m_axis == AXIS_X) { - const short i0 = MAX(0, bestPlane.m_index - downsampling); - const short i1 = static_cast(MIN((maxV[0] - minV[0]) / scale + 0.5, bestPlane.m_index + downsampling)); - plane.m_a = 1.0; - plane.m_b = 0.0; - plane.m_c = 0.0; - plane.m_axis = AXIS_X; - for (short i = i0; i <= i1; ++i) { - double x = minV[0] + scale * i; - plane.m_d = -x; - plane.m_index = i; - planes.PushBack(plane); - } - } - else if (bestPlane.m_axis == AXIS_Y) { - const short j0 = MAX(0, bestPlane.m_index - downsampling); - const short j1 = static_cast(MIN((maxV[1] - minV[1]) / scale + 0.5, bestPlane.m_index + downsampling)); - plane.m_a = 0.0; - plane.m_b = 1.0; - plane.m_c = 0.0; - plane.m_axis = AXIS_Y; - for (short j = j0; j <= j1; ++j) { - double y = minV[1] + scale * j; - plane.m_d = -y; - plane.m_index = j; - planes.PushBack(plane); - } - } - else { - const short k0 = MAX(0, bestPlane.m_index - downsampling); - const short k1 = static_cast(MIN((maxV[2] - minV[2]) / scale + 0.5, bestPlane.m_index + downsampling)); - plane.m_a = 0.0; - plane.m_b = 0.0; - plane.m_c = 1.0; - plane.m_axis = AXIS_Z; - for (short k = k0; k <= k1; ++k) { - double z = minV[2] + scale * k; - plane.m_d = -z; - plane.m_index = k; - planes.PushBack(plane); - } - } -} -inline double ComputeLocalConcavity(const double volume, const double volumeCH) -{ - return fabs(volumeCH - volume) / volumeCH; -} -inline double ComputeConcavity(const double volume, const double volumeCH, const double volume0) -{ - return fabs(volumeCH - volume) / volume0; -} - -//#define DEBUG_TEMP -void VHACD::ComputeBestClippingPlane(const PrimitiveSet* inputPSet, const double volume, const SArray& planes, - const Vec3& preferredCuttingDirection, const double w, const double alpha, const double beta, - const int convexhullDownsampling, const double progress0, const double progress1, Plane& bestPlane, - double& minConcavity, const Parameters& params) -{ - if (GetCancel()) { - return; - } - char msg[256]; - size_t nPrimitives = inputPSet->GetNPrimitives(); - bool oclAcceleration = (nPrimitives > OCL_MIN_NUM_PRIMITIVES && params.m_oclAcceleration && params.m_mode == 0) ? true : false; - int iBest = -1; - int nPlanes = static_cast(planes.Size()); - bool cancel = false; - int done = 0; - double minTotal = MAX_DOUBLE; - double minBalance = MAX_DOUBLE; - double minSymmetry = MAX_DOUBLE; - minConcavity = MAX_DOUBLE; - - SArray >* chPts = new SArray >[2 * m_ompNumProcessors]; - Mesh* chs = new Mesh[2 * m_ompNumProcessors]; - PrimitiveSet* onSurfacePSet = inputPSet->Create(); - inputPSet->SelectOnSurface(onSurfacePSet); - - PrimitiveSet** psets = 0; - if (!params.m_convexhullApproximation) { - psets = new PrimitiveSet*[2 * m_ompNumProcessors]; - for (int i = 0; i < 2 * m_ompNumProcessors; ++i) { - psets[i] = inputPSet->Create(); - } - } - -#ifdef CL_VERSION_1_1 - // allocate OpenCL data structures - cl_mem voxels; - cl_mem* partialVolumes = 0; - size_t globalSize = 0; - size_t nWorkGroups = 0; - double unitVolume = 0.0; - if (oclAcceleration) { - VoxelSet* vset = (VoxelSet*)inputPSet; - const Vec3 minBB = vset->GetMinBB(); - const float fMinBB[4] = { (float)minBB[0], (float)minBB[1], (float)minBB[2], 1.0f }; - const float fSclae[4] = { (float)vset->GetScale(), (float)vset->GetScale(), (float)vset->GetScale(), 0.0f }; - const int nVoxels = (int)nPrimitives; - unitVolume = vset->GetUnitVolume(); - nWorkGroups = (nPrimitives + 4 * m_oclWorkGroupSize - 1) / (4 * m_oclWorkGroupSize); - globalSize = nWorkGroups * m_oclWorkGroupSize; - cl_int error; - voxels = clCreateBuffer(m_oclContext, - CL_MEM_READ_ONLY | CL_MEM_COPY_HOST_PTR, - sizeof(Voxel) * nPrimitives, - vset->GetVoxels(), - &error); - if (error != CL_SUCCESS) { - if (params.m_logger) { - params.m_logger->Log("Couldn't create buffer\n"); - } - SetCancel(true); - } - - partialVolumes = new cl_mem[m_ompNumProcessors]; - for (int i = 0; i < m_ompNumProcessors; ++i) { - partialVolumes[i] = clCreateBuffer(m_oclContext, - CL_MEM_WRITE_ONLY, - sizeof(unsigned int) * 4 * nWorkGroups, - NULL, - &error); - if (error != CL_SUCCESS) { - if (params.m_logger) { - params.m_logger->Log("Couldn't create buffer\n"); - } - SetCancel(true); - break; - } - error = clSetKernelArg(m_oclKernelComputePartialVolumes[i], 0, sizeof(cl_mem), &voxels); - error |= clSetKernelArg(m_oclKernelComputePartialVolumes[i], 1, sizeof(unsigned int), &nVoxels); - error |= clSetKernelArg(m_oclKernelComputePartialVolumes[i], 3, sizeof(float) * 4, fMinBB); - error |= clSetKernelArg(m_oclKernelComputePartialVolumes[i], 4, sizeof(float) * 4, &fSclae); - error |= clSetKernelArg(m_oclKernelComputePartialVolumes[i], 5, sizeof(unsigned int) * 4 * m_oclWorkGroupSize, NULL); - error |= clSetKernelArg(m_oclKernelComputePartialVolumes[i], 6, sizeof(cl_mem), &(partialVolumes[i])); - error |= clSetKernelArg(m_oclKernelComputeSum[i], 0, sizeof(cl_mem), &(partialVolumes[i])); - error |= clSetKernelArg(m_oclKernelComputeSum[i], 2, sizeof(unsigned int) * 4 * m_oclWorkGroupSize, NULL); - if (error != CL_SUCCESS) { - if (params.m_logger) { - params.m_logger->Log("Couldn't kernel atguments \n"); - } - SetCancel(true); - } - } - } -#else // CL_VERSION_1_1 - oclAcceleration = false; -#endif // CL_VERSION_1_1 - -#ifdef DEBUG_TEMP - Timer timerComputeCost; - timerComputeCost.Tic(); -#endif // DEBUG_TEMP - -#if USE_THREAD == 1 && _OPENMP -#pragma omp parallel for -#endif - for (int x = 0; x < nPlanes; ++x) { - int threadID = 0; -#if USE_THREAD == 1 && _OPENMP - threadID = omp_get_thread_num(); -#pragma omp flush(cancel) -#endif - if (!cancel) { - //Update progress - if (GetCancel()) { - cancel = true; -#if USE_THREAD == 1 && _OPENMP -#pragma omp flush(cancel) -#endif - } - Plane plane = planes[x]; - - if (oclAcceleration) { -#ifdef CL_VERSION_1_1 - const float fPlane[4] = { (float)plane.m_a, (float)plane.m_b, (float)plane.m_c, (float)plane.m_d }; - cl_int error = clSetKernelArg(m_oclKernelComputePartialVolumes[threadID], 2, sizeof(float) * 4, fPlane); - if (error != CL_SUCCESS) { - if (params.m_logger) { - params.m_logger->Log("Couldn't kernel atguments \n"); - } - SetCancel(true); - } - - error = clEnqueueNDRangeKernel(m_oclQueue[threadID], m_oclKernelComputePartialVolumes[threadID], - 1, NULL, &globalSize, &m_oclWorkGroupSize, 0, NULL, NULL); - if (error != CL_SUCCESS) { - if (params.m_logger) { - params.m_logger->Log("Couldn't run kernel \n"); - } - SetCancel(true); - } - int nValues = (int)nWorkGroups; - while (nValues > 1) { - error = clSetKernelArg(m_oclKernelComputeSum[threadID], 1, sizeof(int), &nValues); - if (error != CL_SUCCESS) { - if (params.m_logger) { - params.m_logger->Log("Couldn't kernel atguments \n"); - } - SetCancel(true); - } - size_t nWorkGroups = (nValues + m_oclWorkGroupSize - 1) / m_oclWorkGroupSize; - size_t globalSize = nWorkGroups * m_oclWorkGroupSize; - error = clEnqueueNDRangeKernel(m_oclQueue[threadID], m_oclKernelComputeSum[threadID], - 1, NULL, &globalSize, &m_oclWorkGroupSize, 0, NULL, NULL); - if (error != CL_SUCCESS) { - if (params.m_logger) { - params.m_logger->Log("Couldn't run kernel \n"); - } - SetCancel(true); - } - nValues = (int)nWorkGroups; - } -#endif // CL_VERSION_1_1 - } - - Mesh& leftCH = chs[threadID]; - Mesh& rightCH = chs[threadID + m_ompNumProcessors]; - rightCH.ResizePoints(0); - leftCH.ResizePoints(0); - rightCH.ResizeTriangles(0); - leftCH.ResizeTriangles(0); - -// compute convex-hulls -#ifdef TEST_APPROX_CH - double volumeLeftCH1; - double volumeRightCH1; -#endif //TEST_APPROX_CH - if (params.m_convexhullApproximation) { - SArray >& leftCHPts = chPts[threadID]; - SArray >& rightCHPts = chPts[threadID + m_ompNumProcessors]; - rightCHPts.Resize(0); - leftCHPts.Resize(0); - onSurfacePSet->Intersect(plane, &rightCHPts, &leftCHPts, convexhullDownsampling * 32); - inputPSet->GetConvexHull().Clip(plane, rightCHPts, leftCHPts); - rightCH.ComputeConvexHull((double*)rightCHPts.Data(), rightCHPts.Size()); - leftCH.ComputeConvexHull((double*)leftCHPts.Data(), leftCHPts.Size()); -#ifdef TEST_APPROX_CH - Mesh leftCH1; - Mesh rightCH1; - VoxelSet right; - VoxelSet left; - onSurfacePSet->Clip(plane, &right, &left); - right.ComputeConvexHull(rightCH1, convexhullDownsampling); - left.ComputeConvexHull(leftCH1, convexhullDownsampling); - - volumeLeftCH1 = leftCH1.ComputeVolume(); - volumeRightCH1 = rightCH1.ComputeVolume(); -#endif //TEST_APPROX_CH - } - else { - PrimitiveSet* const right = psets[threadID]; - PrimitiveSet* const left = psets[threadID + m_ompNumProcessors]; - onSurfacePSet->Clip(plane, right, left); - right->ComputeConvexHull(rightCH, convexhullDownsampling); - left->ComputeConvexHull(leftCH, convexhullDownsampling); - } - double volumeLeftCH = leftCH.ComputeVolume(); - double volumeRightCH = rightCH.ComputeVolume(); - - // compute clipped volumes - double volumeLeft = 0.0; - double volumeRight = 0.0; - if (oclAcceleration) { -#ifdef CL_VERSION_1_1 - unsigned int volumes[4]; - cl_int error = clEnqueueReadBuffer(m_oclQueue[threadID], partialVolumes[threadID], CL_TRUE, - 0, sizeof(unsigned int) * 4, volumes, 0, NULL, NULL); - size_t nPrimitivesRight = volumes[0] + volumes[1] + volumes[2] + volumes[3]; - size_t nPrimitivesLeft = nPrimitives - nPrimitivesRight; - volumeRight = nPrimitivesRight * unitVolume; - volumeLeft = nPrimitivesLeft * unitVolume; - if (error != CL_SUCCESS) { - if (params.m_logger) { - params.m_logger->Log("Couldn't read buffer \n"); - } - SetCancel(true); - } -#endif // CL_VERSION_1_1 - } - else { - inputPSet->ComputeClippedVolumes(plane, volumeRight, volumeLeft); - } - double concavityLeft = ComputeConcavity(volumeLeft, volumeLeftCH, m_volumeCH0); - double concavityRight = ComputeConcavity(volumeRight, volumeRightCH, m_volumeCH0); - double concavity = (concavityLeft + concavityRight); - - // compute cost - double balance = alpha * fabs(volumeLeft - volumeRight) / m_volumeCH0; - double d = w * (preferredCuttingDirection[0] * plane.m_a + preferredCuttingDirection[1] * plane.m_b + preferredCuttingDirection[2] * plane.m_c); - double symmetry = beta * d; - double total = concavity + balance + symmetry; - -#if USE_THREAD == 1 && _OPENMP -#pragma omp critical -#endif - { - if (total < minTotal || (total == minTotal && x < iBest)) { - minConcavity = concavity; - minBalance = balance; - minSymmetry = symmetry; - bestPlane = plane; - minTotal = total; - iBest = x; - } - ++done; - if (!(done & 127)) // reduce update frequency - { - double progress = done * (progress1 - progress0) / nPlanes + progress0; - Update(m_stageProgress, progress, params); - } - } - } - } - -#ifdef DEBUG_TEMP - timerComputeCost.Toc(); - printf_s("Cost[%i] = %f\n", nPlanes, timerComputeCost.GetElapsedTime()); -#endif // DEBUG_TEMP - -#ifdef CL_VERSION_1_1 - if (oclAcceleration) { - clReleaseMemObject(voxels); - for (int i = 0; i < m_ompNumProcessors; ++i) { - clReleaseMemObject(partialVolumes[i]); - } - delete[] partialVolumes; - } -#endif // CL_VERSION_1_1 - - if (psets) { - for (int i = 0; i < 2 * m_ompNumProcessors; ++i) { - delete psets[i]; - } - delete[] psets; - } - delete onSurfacePSet; - delete[] chPts; - delete[] chs; - if (params.m_logger) { - sprintf(msg, "\n\t\t\t Best %04i T=%2.6f C=%2.6f B=%2.6f S=%2.6f (%1.1f, %1.1f, %1.1f, %3.3f)\n\n", iBest, minTotal, minConcavity, minBalance, minSymmetry, bestPlane.m_a, bestPlane.m_b, bestPlane.m_c, bestPlane.m_d); - params.m_logger->Log(msg); - } -} -void VHACD::ComputeACD(const Parameters& params) -{ - if (GetCancel()) { - return; - } - m_timer.Tic(); - - m_stage = "Approximate Convex Decomposition"; - m_stageProgress = 0.0; - std::ostringstream msg; - if (params.m_logger) { - msg << "+ " << m_stage << std::endl; - params.m_logger->Log(msg.str().c_str()); - } - - SArray parts; - SArray inputParts; - SArray temp; - inputParts.PushBack(m_pset); - m_pset = 0; - SArray planes; - SArray planesRef; - int sub = 0; - bool firstIteration = true; - m_volumeCH0 = 1.0; - while (sub++ < params.m_depth && inputParts.Size() > 0 && !m_cancel) { - msg.str(""); - msg << "Subdivision level " << sub; - m_operation = msg.str(); - - if (params.m_logger) { - msg.str(""); - msg << "\t Subdivision level " << sub << std::endl; - params.m_logger->Log(msg.str().c_str()); - } - - double maxConcavity = 0.0; - const size_t nInputParts = inputParts.Size(); - Update(m_stageProgress, 0.0, params); - for (size_t p = 0; p < nInputParts && !m_cancel; ++p) { - const double progress0 = p * 100.0 / nInputParts; - const double progress1 = (p + 0.75) * 100.0 / nInputParts; - const double progress2 = (p + 1.00) * 100.0 / nInputParts; - - Update(m_stageProgress, progress0, params); - - PrimitiveSet* pset = inputParts[p]; - inputParts[p] = 0; - double volume = pset->ComputeVolume(); - pset->ComputeBB(); - pset->ComputePrincipalAxes(); - if (params.m_pca) { - pset->AlignToPrincipalAxes(); - } - - pset->ComputeConvexHull(pset->GetConvexHull()); - double volumeCH = fabs(pset->GetConvexHull().ComputeVolume()); - if (firstIteration) { - m_volumeCH0 = volumeCH; - } - - double concavity = ComputeConcavity(volume, volumeCH, m_volumeCH0); - double error = 1.01 * pset->ComputeMaxVolumeError() / m_volumeCH0; - - if (firstIteration) { - firstIteration = false; - } - - if (params.m_logger) { - msg.str(""); - msg << "\t -> Part[" << p - << "] C = " << concavity - << ", E = " << error - << ", VS = " << pset->GetNPrimitivesOnSurf() - << ", VI = " << pset->GetNPrimitivesInsideSurf() - << std::endl; - params.m_logger->Log(msg.str().c_str()); - } - - if (concavity > params.m_concavity && concavity > error) { - Vec3 preferredCuttingDirection; - double w = ComputePreferredCuttingDirection(pset, preferredCuttingDirection); - planes.Resize(0); - if (params.m_mode == 0) { - VoxelSet* vset = (VoxelSet*)pset; - ComputeAxesAlignedClippingPlanes(*vset, params.m_planeDownsampling, planes); - } - else { - TetrahedronSet* tset = (TetrahedronSet*)pset; - ComputeAxesAlignedClippingPlanes(*tset, params.m_planeDownsampling, planes); - } - - if (params.m_logger) { - msg.str(""); - msg << "\t\t [Regular sampling] Number of clipping planes " << planes.Size() << std::endl; - params.m_logger->Log(msg.str().c_str()); - } - - Plane bestPlane; - double minConcavity = MAX_DOUBLE; - ComputeBestClippingPlane(pset, - volume, - planes, - preferredCuttingDirection, - w, - concavity * params.m_alpha, - concavity * params.m_beta, - params.m_convexhullDownsampling, - progress0, - progress1, - bestPlane, - minConcavity, - params); - if (!m_cancel && (params.m_planeDownsampling > 1 || params.m_convexhullDownsampling > 1)) { - planesRef.Resize(0); - - if (params.m_mode == 0) { - VoxelSet* vset = (VoxelSet*)pset; - RefineAxesAlignedClippingPlanes(*vset, bestPlane, params.m_planeDownsampling, planesRef); - } - else { - TetrahedronSet* tset = (TetrahedronSet*)pset; - RefineAxesAlignedClippingPlanes(*tset, bestPlane, params.m_planeDownsampling, planesRef); - } - - if (params.m_logger) { - msg.str(""); - msg << "\t\t [Refining] Number of clipping planes " << planesRef.Size() << std::endl; - params.m_logger->Log(msg.str().c_str()); - } - ComputeBestClippingPlane(pset, - volume, - planesRef, - preferredCuttingDirection, - w, - concavity * params.m_alpha, - concavity * params.m_beta, - 1, // convexhullDownsampling = 1 - progress1, - progress2, - bestPlane, - minConcavity, - params); - } - if (GetCancel()) { - delete pset; // clean up - break; - } - else { - if (maxConcavity < minConcavity) { - maxConcavity = minConcavity; - } - PrimitiveSet* bestLeft = pset->Create(); - PrimitiveSet* bestRight = pset->Create(); - temp.PushBack(bestLeft); - temp.PushBack(bestRight); - pset->Clip(bestPlane, bestRight, bestLeft); - if (params.m_pca) { - bestRight->RevertAlignToPrincipalAxes(); - bestLeft->RevertAlignToPrincipalAxes(); - } - delete pset; - } - } - else { - if (params.m_pca) { - pset->RevertAlignToPrincipalAxes(); - } - parts.PushBack(pset); - } - } - - Update(95.0 * (1.0 - maxConcavity) / (1.0 - params.m_concavity), 100.0, params); - if (GetCancel()) { - const size_t nTempParts = temp.Size(); - for (size_t p = 0; p < nTempParts; ++p) { - delete temp[p]; - } - temp.Resize(0); - } - else { - inputParts = temp; - temp.Resize(0); - } - } - const size_t nInputParts = inputParts.Size(); - for (size_t p = 0; p < nInputParts; ++p) { - parts.PushBack(inputParts[p]); - } - - if (GetCancel()) { - const size_t nParts = parts.Size(); - for (size_t p = 0; p < nParts; ++p) { - delete parts[p]; - } - return; - } - - m_overallProgress = 90.0; - Update(m_stageProgress, 100.0, params); - - msg.str(""); - msg << "Generate convex-hulls"; - m_operation = msg.str(); - size_t nConvexHulls = parts.Size(); - if (params.m_logger) { - msg.str(""); - msg << "+ Generate " << nConvexHulls << " convex-hulls " << std::endl; - params.m_logger->Log(msg.str().c_str()); - } - - Update(m_stageProgress, 0.0, params); - m_convexHulls.Resize(0); - for (size_t p = 0; p < nConvexHulls && !m_cancel; ++p) { - Update(m_stageProgress, p * 100.0 / nConvexHulls, params); - m_convexHulls.PushBack(new Mesh); - parts[p]->ComputeConvexHull(*m_convexHulls[p]); - size_t nv = m_convexHulls[p]->GetNPoints(); - double x, y, z; - for (size_t i = 0; i < nv; ++i) { - Vec3& pt = m_convexHulls[p]->GetPoint(i); - x = pt[0]; - y = pt[1]; - z = pt[2]; - pt[0] = m_rot[0][0] * x + m_rot[0][1] * y + m_rot[0][2] * z + m_barycenter[0]; - pt[1] = m_rot[1][0] * x + m_rot[1][1] * y + m_rot[1][2] * z + m_barycenter[1]; - pt[2] = m_rot[2][0] * x + m_rot[2][1] * y + m_rot[2][2] * z + m_barycenter[2]; - } - } - - const size_t nParts = parts.Size(); - for (size_t p = 0; p < nParts; ++p) { - delete parts[p]; - parts[p] = 0; - } - parts.Resize(0); - - if (GetCancel()) { - const size_t nConvexHulls = m_convexHulls.Size(); - for (size_t p = 0; p < nConvexHulls; ++p) { - delete m_convexHulls[p]; - } - m_convexHulls.Clear(); - return; - } - - m_overallProgress = 95.0; - Update(100.0, 100.0, params); - m_timer.Toc(); - if (params.m_logger) { - msg.str(""); - msg << "\t time " << m_timer.GetElapsedTime() / 1000.0 << "s" << std::endl; - params.m_logger->Log(msg.str().c_str()); - } -} -void AddPoints(const Mesh* const mesh, SArray >& pts) -{ - const int n = (int)mesh->GetNPoints(); - for (int i = 0; i < n; ++i) { - pts.PushBack(mesh->GetPoint(i)); - } -} -void ComputeConvexHull(const Mesh* const ch1, const Mesh* const ch2, SArray >& pts, Mesh* const combinedCH) -{ - pts.Resize(0); - AddPoints(ch1, pts); - AddPoints(ch2, pts); - - btConvexHullComputer ch; - ch.compute((double*)pts.Data(), 3 * sizeof(double), (int)pts.Size(), -1.0, -1.0); - combinedCH->ResizePoints(0); - combinedCH->ResizeTriangles(0); - for (int v = 0; v < ch.vertices.size(); v++) { - combinedCH->AddPoint(Vec3(ch.vertices[v].getX(), ch.vertices[v].getY(), ch.vertices[v].getZ())); - } - const int nt = ch.faces.size(); - for (int t = 0; t < nt; ++t) { - const btConvexHullComputer::Edge* sourceEdge = &(ch.edges[ch.faces[t]]); - int a = sourceEdge->getSourceVertex(); - int b = sourceEdge->getTargetVertex(); - const btConvexHullComputer::Edge* edge = sourceEdge->getNextEdgeOfFace(); - int c = edge->getTargetVertex(); - while (c != a) { - combinedCH->AddTriangle(Vec3(a, b, c)); - edge = edge->getNextEdgeOfFace(); - b = c; - c = edge->getTargetVertex(); - } - } -} -void VHACD::MergeConvexHulls(const Parameters& params) -{ - if (GetCancel()) { - return; - } - m_timer.Tic(); - - m_stage = "Merge Convex Hulls"; - - std::ostringstream msg; - if (params.m_logger) { - msg << "+ " << m_stage << std::endl; - params.m_logger->Log(msg.str().c_str()); - } - - size_t nConvexHulls = m_convexHulls.Size(); - int iteration = 0; - if (nConvexHulls > 1 && !m_cancel) { - const double threshold = params.m_gamma; - SArray > pts; - Mesh combinedCH; - - // Populate the cost matrix - size_t idx = 0; - SArray costMatrix; - costMatrix.Resize(((nConvexHulls * nConvexHulls) - nConvexHulls) >> 1); - for (size_t p1 = 1; p1 < nConvexHulls; ++p1) { - const float volume1 = m_convexHulls[p1]->ComputeVolume(); - for (size_t p2 = 0; p2 < p1; ++p2) { - ComputeConvexHull(m_convexHulls[p1], m_convexHulls[p2], pts, &combinedCH); - costMatrix[idx++] = ComputeConcavity(volume1 + m_convexHulls[p2]->ComputeVolume(), combinedCH.ComputeVolume(), m_volumeCH0); - } - } - - // Until we cant merge below the maximum cost - size_t costSize = m_convexHulls.Size(); - while (!m_cancel) { - msg.str(""); - msg << "Iteration " << iteration++; - m_operation = msg.str(); - - // Search for lowest cost - float bestCost = (std::numeric_limits::max)(); - const size_t addr = FindMinimumElement(costMatrix.Data(), &bestCost, 0, costMatrix.Size()); - - // Check if we should merge these hulls - if (bestCost >= threshold) { - break; - } - double nr = 1 + (8 * addr); - const size_t addrI = (static_cast(sqrt(nr)) - 1) >> 1; - const size_t p1 = addrI + 1; - const size_t p2 = addr - ((addrI * (addrI + 1)) >> 1); - assert(p1 >= 0); - assert(p2 >= 0); - assert(p1 < costSize); - assert(p2 < costSize); - - if (params.m_logger) { - msg.str(""); - msg << "\t\t Merging (" << p1 << ", " << p2 << ") " << bestCost << std::endl - << std::endl; - params.m_logger->Log(msg.str().c_str()); - } - - // Make the lowest cost row and column into a new hull - Mesh* cch = new Mesh; - ComputeConvexHull(m_convexHulls[p1], m_convexHulls[p2], pts, cch); - delete m_convexHulls[p2]; - m_convexHulls[p2] = cch; - - delete m_convexHulls[p1]; - std::swap(m_convexHulls[p1], m_convexHulls[m_convexHulls.Size() - 1]); - m_convexHulls.PopBack(); - - costSize = costSize - 1; - - // Calculate costs versus the new hull - size_t rowIdx = ((p2 - 1) * p2) >> 1; - const float volume1 = m_convexHulls[p2]->ComputeVolume(); - for (size_t i = 0; (i < p2) && (!m_cancel); ++i) { - ComputeConvexHull(m_convexHulls[p2], m_convexHulls[i], pts, &combinedCH); - costMatrix[rowIdx++] = ComputeConcavity(volume1 + m_convexHulls[i]->ComputeVolume(), combinedCH.ComputeVolume(), m_volumeCH0); - } - - rowIdx += p2; - for (size_t i = p2 + 1; (i < costSize) && (!m_cancel); ++i) { - ComputeConvexHull(m_convexHulls[p2], m_convexHulls[i], pts, &combinedCH); - costMatrix[rowIdx] = ComputeConcavity(volume1 + m_convexHulls[i]->ComputeVolume(), combinedCH.ComputeVolume(), m_volumeCH0); - rowIdx += i; - assert(rowIdx >= 0); - } - - // Move the top column in to replace its space - const size_t erase_idx = ((costSize - 1) * costSize) >> 1; - if (p1 < costSize) { - rowIdx = (addrI * p1) >> 1; - size_t top_row = erase_idx; - for (size_t i = 0; i < p1; ++i) { - if (i != p2) { - costMatrix[rowIdx] = costMatrix[top_row]; - } - ++rowIdx; - ++top_row; - } - - ++top_row; - rowIdx += p1; - for (size_t i = p1 + 1; i < (costSize + 1); ++i) { - costMatrix[rowIdx] = costMatrix[top_row++]; - rowIdx += i; - assert(rowIdx >= 0); - } - } - costMatrix.Resize(erase_idx); - } - } - m_overallProgress = 99.0; - Update(100.0, 100.0, params); - m_timer.Toc(); - if (params.m_logger) { - msg.str(""); - msg << "\t time " << m_timer.GetElapsedTime() / 1000.0 << "s" << std::endl; - params.m_logger->Log(msg.str().c_str()); - } -} -void SimplifyConvexHull(Mesh* const ch, const size_t nvertices, const double minVolume) -{ - if (nvertices <= 4) { - return; - } - ICHull icHull; - icHull.AddPoints(ch->GetPointsBuffer(), ch->GetNPoints()); - icHull.Process((unsigned int)nvertices, minVolume); - TMMesh& mesh = icHull.GetMesh(); - const size_t nT = mesh.GetNTriangles(); - const size_t nV = mesh.GetNVertices(); - ch->ResizePoints(nV); - ch->ResizeTriangles(nT); - mesh.GetIFS(ch->GetPointsBuffer(), ch->GetTrianglesBuffer()); -} -void VHACD::SimplifyConvexHulls(const Parameters& params) -{ - if (m_cancel || params.m_maxNumVerticesPerCH < 4) { - return; - } - m_timer.Tic(); - - m_stage = "Simplify convex-hulls"; - m_operation = "Simplify convex-hulls"; - - std::ostringstream msg; - const size_t nConvexHulls = m_convexHulls.Size(); - if (params.m_logger) { - msg << "+ Simplify " << nConvexHulls << " convex-hulls " << std::endl; - params.m_logger->Log(msg.str().c_str()); - } - - Update(0.0, 0.0, params); - for (size_t i = 0; i < nConvexHulls && !m_cancel; ++i) { - if (params.m_logger) { - msg.str(""); - msg << "\t\t Simplify CH[" << std::setfill('0') << std::setw(5) << i << "] " << m_convexHulls[i]->GetNPoints() << " V, " << m_convexHulls[i]->GetNTriangles() << " T" << std::endl; - params.m_logger->Log(msg.str().c_str()); - } - SimplifyConvexHull(m_convexHulls[i], params.m_maxNumVerticesPerCH, m_volumeCH0 * params.m_minVolumePerCH); - } - - m_overallProgress = 100.0; - Update(100.0, 100.0, params); - m_timer.Toc(); - if (params.m_logger) { - msg.str(""); - msg << "\t time " << m_timer.GetElapsedTime() / 1000.0 << "s" << std::endl; - params.m_logger->Log(msg.str().c_str()); - } -} -} diff --git a/extern/bullet/src/Extras/VHACD/src/btAlignedAllocator.cpp b/extern/bullet/src/Extras/VHACD/src/btAlignedAllocator.cpp deleted file mode 100644 index e69442f6733b..000000000000 --- a/extern/bullet/src/Extras/VHACD/src/btAlignedAllocator.cpp +++ /dev/null @@ -1,176 +0,0 @@ -/* -Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#include "btAlignedAllocator.h" - -int gNumAlignedAllocs = 0; -int gNumAlignedFree = 0; -int gTotalBytesAlignedAllocs = 0; //detect memory leaks - -static void* btAllocDefault(size_t size) -{ - return malloc(size); -} - -static void btFreeDefault(void* ptr) -{ - free(ptr); -} - -static btAllocFunc* sAllocFunc = btAllocDefault; -static btFreeFunc* sFreeFunc = btFreeDefault; - -#if defined(BT_HAS_ALIGNED_ALLOCATOR) -#include -static void* btAlignedAllocDefault(size_t size, int alignment) -{ - return _aligned_malloc(size, (size_t)alignment); -} - -static void btAlignedFreeDefault(void* ptr) -{ - _aligned_free(ptr); -} -#elif defined(__CELLOS_LV2__) -#include - -static inline void* btAlignedAllocDefault(size_t size, int alignment) -{ - return memalign(alignment, size); -} - -static inline void btAlignedFreeDefault(void* ptr) -{ - free(ptr); -} -#else -static inline void* btAlignedAllocDefault(size_t size, int alignment) -{ - void* ret; - char* real; - unsigned long offset; - - real = (char*)sAllocFunc(size + sizeof(void*) + (alignment - 1)); - if (real) { - offset = (alignment - (unsigned long)(real + sizeof(void*))) & (alignment - 1); - ret = (void*)((real + sizeof(void*)) + offset); - *((void**)(ret)-1) = (void*)(real); - } - else { - ret = (void*)(real); - } - return (ret); -} - -static inline void btAlignedFreeDefault(void* ptr) -{ - void* real; - - if (ptr) { - real = *((void**)(ptr)-1); - sFreeFunc(real); - } -} -#endif - -static btAlignedAllocFunc* sAlignedAllocFunc = btAlignedAllocDefault; -static btAlignedFreeFunc* sAlignedFreeFunc = btAlignedFreeDefault; - -void btAlignedAllocSetCustomAligned(btAlignedAllocFunc* allocFunc, btAlignedFreeFunc* freeFunc) -{ - sAlignedAllocFunc = allocFunc ? allocFunc : btAlignedAllocDefault; - sAlignedFreeFunc = freeFunc ? freeFunc : btAlignedFreeDefault; -} - -void btAlignedAllocSetCustom(btAllocFunc* allocFunc, btFreeFunc* freeFunc) -{ - sAllocFunc = allocFunc ? allocFunc : btAllocDefault; - sFreeFunc = freeFunc ? freeFunc : btFreeDefault; -} - -#ifdef BT_DEBUG_MEMORY_ALLOCATIONS -//this generic allocator provides the total allocated number of bytes -#include - -void* btAlignedAllocInternal(size_t size, int alignment, int line, char* filename) -{ - void* ret; - char* real; - unsigned long offset; - - gTotalBytesAlignedAllocs += size; - gNumAlignedAllocs++; - - real = (char*)sAllocFunc(size + 2 * sizeof(void*) + (alignment - 1)); - if (real) { - offset = (alignment - (unsigned long)(real + 2 * sizeof(void*))) & (alignment - 1); - ret = (void*)((real + 2 * sizeof(void*)) + offset); - *((void**)(ret)-1) = (void*)(real); - *((int*)(ret)-2) = size; - } - else { - ret = (void*)(real); //?? - } - - printf("allocation#%d at address %x, from %s,line %d, size %d\n", gNumAlignedAllocs, real, filename, line, size); - - int* ptr = (int*)ret; - *ptr = 12; - return (ret); -} - -void btAlignedFreeInternal(void* ptr, int line, char* filename) -{ - - void* real; - gNumAlignedFree++; - - if (ptr) { - real = *((void**)(ptr)-1); - int size = *((int*)(ptr)-2); - gTotalBytesAlignedAllocs -= size; - - printf("free #%d at address %x, from %s,line %d, size %d\n", gNumAlignedFree, real, filename, line, size); - - sFreeFunc(real); - } - else { - printf("NULL ptr\n"); - } -} - -#else //BT_DEBUG_MEMORY_ALLOCATIONS - -void* btAlignedAllocInternal(size_t size, int alignment) -{ - gNumAlignedAllocs++; - void* ptr; - ptr = sAlignedAllocFunc(size, alignment); - // printf("btAlignedAllocInternal %d, %x\n",size,ptr); - return ptr; -} - -void btAlignedFreeInternal(void* ptr) -{ - if (!ptr) { - return; - } - - gNumAlignedFree++; - // printf("btAlignedFreeInternal %x\n",ptr); - sAlignedFreeFunc(ptr); -} - -#endif //BT_DEBUG_MEMORY_ALLOCATIONS diff --git a/extern/bullet/src/Extras/VHACD/src/btConvexHullComputer.cpp b/extern/bullet/src/Extras/VHACD/src/btConvexHullComputer.cpp deleted file mode 100644 index 9072260d4f53..000000000000 --- a/extern/bullet/src/Extras/VHACD/src/btConvexHullComputer.cpp +++ /dev/null @@ -1,2475 +0,0 @@ -/* -Copyright (c) 2011 Ole Kniemeyer, MAXON, www.maxon.net - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#include - -#include "LinearMath/btAlignedObjectArray.h" -#include "Extras/VHACD/inc/btConvexHullComputer.h" -#include "LinearMath/btMinMax.h" -#include "LinearMath/btVector3.h" - -#ifdef __GNUC__ -#include -#elif defined(_MSC_VER) -typedef __int32 int32_t; -typedef __int64 int64_t; -typedef unsigned __int32 uint32_t; -typedef unsigned __int64 uint64_t; -#else -typedef int int32_t; -typedef long long int int64_t; -typedef unsigned int uint32_t; -typedef unsigned long long int uint64_t; -#endif - -//The definition of USE_X86_64_ASM is moved into the build system. You can enable it manually by commenting out the following lines -//#if (defined(__GNUC__) && defined(__x86_64__) && !defined(__ICL)) // || (defined(__ICL) && defined(_M_X64)) bug in Intel compiler, disable inline assembly -// #define USE_X86_64_ASM -//#endif - -//#define DEBUG_CONVEX_HULL -//#define SHOW_ITERATIONS - -#if defined(DEBUG_CONVEX_HULL) || defined(SHOW_ITERATIONS) -#include -#endif - -// Convex hull implementation based on Preparata and Hong -// Ole Kniemeyer, MAXON Computer GmbH -class btConvexHullInternal { -public: - class Point64 { - public: - int64_t x; - int64_t y; - int64_t z; - - Point64(int64_t x, int64_t y, int64_t z) - : x(x) - , y(y) - , z(z) - { - } - - bool isZero() - { - return (x == 0) && (y == 0) && (z == 0); - } - - int64_t dot(const Point64& b) const - { - return x * b.x + y * b.y + z * b.z; - } - }; - - class Point32 { - public: - int32_t x; - int32_t y; - int32_t z; - int index; - - Point32() - { - } - - Point32(int32_t x, int32_t y, int32_t z) - : x(x) - , y(y) - , z(z) - , index(-1) - { - } - - bool operator==(const Point32& b) const - { - return (x == b.x) && (y == b.y) && (z == b.z); - } - - bool operator!=(const Point32& b) const - { - return (x != b.x) || (y != b.y) || (z != b.z); - } - - bool isZero() - { - return (x == 0) && (y == 0) && (z == 0); - } - - Point64 cross(const Point32& b) const - { - return Point64(y * b.z - z * b.y, z * b.x - x * b.z, x * b.y - y * b.x); - } - - Point64 cross(const Point64& b) const - { - return Point64(y * b.z - z * b.y, z * b.x - x * b.z, x * b.y - y * b.x); - } - - int64_t dot(const Point32& b) const - { - return x * b.x + y * b.y + z * b.z; - } - - int64_t dot(const Point64& b) const - { - return x * b.x + y * b.y + z * b.z; - } - - Point32 operator+(const Point32& b) const - { - return Point32(x + b.x, y + b.y, z + b.z); - } - - Point32 operator-(const Point32& b) const - { - return Point32(x - b.x, y - b.y, z - b.z); - } - }; - - class Int128 { - public: - uint64_t low; - uint64_t high; - - Int128() - { - } - - Int128(uint64_t low, uint64_t high) - : low(low) - , high(high) - { - } - - Int128(uint64_t low) - : low(low) - , high(0) - { - } - - Int128(int64_t value) - : low(value) - , high((value >= 0) ? 0 : (uint64_t)-1LL) - { - } - - static Int128 mul(int64_t a, int64_t b); - - static Int128 mul(uint64_t a, uint64_t b); - - Int128 operator-() const - { - return Int128((uint64_t) - (int64_t)low, ~high + (low == 0)); - } - - Int128 operator+(const Int128& b) const - { -#ifdef USE_X86_64_ASM - Int128 result; - __asm__("addq %[bl], %[rl]\n\t" - "adcq %[bh], %[rh]\n\t" - : [rl] "=r"(result.low), [rh] "=r"(result.high) - : "0"(low), "1"(high), [bl] "g"(b.low), [bh] "g"(b.high) - : "cc"); - return result; -#else - uint64_t lo = low + b.low; - return Int128(lo, high + b.high + (lo < low)); -#endif - } - - Int128 operator-(const Int128& b) const - { -#ifdef USE_X86_64_ASM - Int128 result; - __asm__("subq %[bl], %[rl]\n\t" - "sbbq %[bh], %[rh]\n\t" - : [rl] "=r"(result.low), [rh] "=r"(result.high) - : "0"(low), "1"(high), [bl] "g"(b.low), [bh] "g"(b.high) - : "cc"); - return result; -#else - return *this + -b; -#endif - } - - Int128& operator+=(const Int128& b) - { -#ifdef USE_X86_64_ASM - __asm__("addq %[bl], %[rl]\n\t" - "adcq %[bh], %[rh]\n\t" - : [rl] "=r"(low), [rh] "=r"(high) - : "0"(low), "1"(high), [bl] "g"(b.low), [bh] "g"(b.high) - : "cc"); -#else - uint64_t lo = low + b.low; - if (lo < low) { - ++high; - } - low = lo; - high += b.high; -#endif - return *this; - } - - Int128& operator++() - { - if (++low == 0) { - ++high; - } - return *this; - } - - Int128 operator*(int64_t b) const; - - btScalar toScalar() const - { - return ((int64_t)high >= 0) ? btScalar(high) * (btScalar(0x100000000LL) * btScalar(0x100000000LL)) + btScalar(low) - : -(-*this).toScalar(); - } - - int getSign() const - { - return ((int64_t)high < 0) ? -1 : (high || low) ? 1 : 0; - } - - bool operator<(const Int128& b) const - { - return (high < b.high) || ((high == b.high) && (low < b.low)); - } - - int ucmp(const Int128& b) const - { - if (high < b.high) { - return -1; - } - if (high > b.high) { - return 1; - } - if (low < b.low) { - return -1; - } - if (low > b.low) { - return 1; - } - return 0; - } - }; - - class Rational64 { - private: - uint64_t m_numerator; - uint64_t m_denominator; - int sign; - - public: - Rational64(int64_t numerator, int64_t denominator) - { - if (numerator > 0) { - sign = 1; - m_numerator = (uint64_t)numerator; - } - else if (numerator < 0) { - sign = -1; - m_numerator = (uint64_t)-numerator; - } - else { - sign = 0; - m_numerator = 0; - } - if (denominator > 0) { - m_denominator = (uint64_t)denominator; - } - else if (denominator < 0) { - sign = -sign; - m_denominator = (uint64_t)-denominator; - } - else { - m_denominator = 0; - } - } - - bool isNegativeInfinity() const - { - return (sign < 0) && (m_denominator == 0); - } - - bool isNaN() const - { - return (sign == 0) && (m_denominator == 0); - } - - int compare(const Rational64& b) const; - - btScalar toScalar() const - { - return sign * ((m_denominator == 0) ? SIMD_INFINITY : (btScalar)m_numerator / m_denominator); - } - }; - - class Rational128 { - private: - Int128 numerator; - Int128 denominator; - int sign; - bool isInt64; - - public: - Rational128(int64_t value) - { - if (value > 0) { - sign = 1; - this->numerator = value; - } - else if (value < 0) { - sign = -1; - this->numerator = -value; - } - else { - sign = 0; - this->numerator = (uint64_t)0; - } - this->denominator = (uint64_t)1; - isInt64 = true; - } - - Rational128(const Int128& numerator, const Int128& denominator) - { - sign = numerator.getSign(); - if (sign >= 0) { - this->numerator = numerator; - } - else { - this->numerator = -numerator; - } - int dsign = denominator.getSign(); - if (dsign >= 0) { - this->denominator = denominator; - } - else { - sign = -sign; - this->denominator = -denominator; - } - isInt64 = false; - } - - int compare(const Rational128& b) const; - - int compare(int64_t b) const; - - btScalar toScalar() const - { - return sign * ((denominator.getSign() == 0) ? SIMD_INFINITY : numerator.toScalar() / denominator.toScalar()); - } - }; - - class PointR128 { - public: - Int128 x; - Int128 y; - Int128 z; - Int128 denominator; - - PointR128() - { - } - - PointR128(Int128 x, Int128 y, Int128 z, Int128 denominator) - : x(x) - , y(y) - , z(z) - , denominator(denominator) - { - } - - btScalar xvalue() const - { - return x.toScalar() / denominator.toScalar(); - } - - btScalar yvalue() const - { - return y.toScalar() / denominator.toScalar(); - } - - btScalar zvalue() const - { - return z.toScalar() / denominator.toScalar(); - } - }; - - class Edge; - class Face; - - class Vertex { - public: - Vertex* next; - Vertex* prev; - Edge* edges; - Face* firstNearbyFace; - Face* lastNearbyFace; - PointR128 point128; - Point32 point; - int copy; - - Vertex() - : next(NULL) - , prev(NULL) - , edges(NULL) - , firstNearbyFace(NULL) - , lastNearbyFace(NULL) - , copy(-1) - { - } - -#ifdef DEBUG_CONVEX_HULL - void print() - { - printf("V%d (%d, %d, %d)", point.index, point.x, point.y, point.z); - } - - void printGraph(); -#endif - - Point32 operator-(const Vertex& b) const - { - return point - b.point; - } - - Rational128 dot(const Point64& b) const - { - return (point.index >= 0) ? Rational128(point.dot(b)) - : Rational128(point128.x * b.x + point128.y * b.y + point128.z * b.z, point128.denominator); - } - - btScalar xvalue() const - { - return (point.index >= 0) ? btScalar(point.x) : point128.xvalue(); - } - - btScalar yvalue() const - { - return (point.index >= 0) ? btScalar(point.y) : point128.yvalue(); - } - - btScalar zvalue() const - { - return (point.index >= 0) ? btScalar(point.z) : point128.zvalue(); - } - - void receiveNearbyFaces(Vertex* src) - { - if (lastNearbyFace) { - lastNearbyFace->nextWithSameNearbyVertex = src->firstNearbyFace; - } - else { - firstNearbyFace = src->firstNearbyFace; - } - if (src->lastNearbyFace) { - lastNearbyFace = src->lastNearbyFace; - } - for (Face* f = src->firstNearbyFace; f; f = f->nextWithSameNearbyVertex) { - btAssert(f->nearbyVertex == src); - f->nearbyVertex = this; - } - src->firstNearbyFace = NULL; - src->lastNearbyFace = NULL; - } - }; - - class Edge { - public: - Edge* next; - Edge* prev; - Edge* reverse; - Vertex* target; - Face* face; - int copy; - - ~Edge() - { - next = NULL; - prev = NULL; - reverse = NULL; - target = NULL; - face = NULL; - } - - void link(Edge* n) - { - btAssert(reverse->target == n->reverse->target); - next = n; - n->prev = this; - } - -#ifdef DEBUG_CONVEX_HULL - void print() - { - printf("E%p : %d -> %d, n=%p p=%p (0 %d\t%d\t%d) -> (%d %d %d)", this, reverse->target->point.index, target->point.index, next, prev, - reverse->target->point.x, reverse->target->point.y, reverse->target->point.z, target->point.x, target->point.y, target->point.z); - } -#endif - }; - - class Face { - public: - Face* next; - Vertex* nearbyVertex; - Face* nextWithSameNearbyVertex; - Point32 origin; - Point32 dir0; - Point32 dir1; - - Face() - : next(NULL) - , nearbyVertex(NULL) - , nextWithSameNearbyVertex(NULL) - { - } - - void init(Vertex* a, Vertex* b, Vertex* c) - { - nearbyVertex = a; - origin = a->point; - dir0 = *b - *a; - dir1 = *c - *a; - if (a->lastNearbyFace) { - a->lastNearbyFace->nextWithSameNearbyVertex = this; - } - else { - a->firstNearbyFace = this; - } - a->lastNearbyFace = this; - } - - Point64 getNormal() - { - return dir0.cross(dir1); - } - }; - - template - class DMul { - private: - static uint32_t high(uint64_t value) - { - return (uint32_t)(value >> 32); - } - - static uint32_t low(uint64_t value) - { - return (uint32_t)value; - } - - static uint64_t mul(uint32_t a, uint32_t b) - { - return (uint64_t)a * (uint64_t)b; - } - - static void shlHalf(uint64_t& value) - { - value <<= 32; - } - - static uint64_t high(Int128 value) - { - return value.high; - } - - static uint64_t low(Int128 value) - { - return value.low; - } - - static Int128 mul(uint64_t a, uint64_t b) - { - return Int128::mul(a, b); - } - - static void shlHalf(Int128& value) - { - value.high = value.low; - value.low = 0; - } - - public: - static void mul(UWord a, UWord b, UWord& resLow, UWord& resHigh) - { - UWord p00 = mul(low(a), low(b)); - UWord p01 = mul(low(a), high(b)); - UWord p10 = mul(high(a), low(b)); - UWord p11 = mul(high(a), high(b)); - UWord p0110 = UWord(low(p01)) + UWord(low(p10)); - p11 += high(p01); - p11 += high(p10); - p11 += high(p0110); - shlHalf(p0110); - p00 += p0110; - if (p00 < p0110) { - ++p11; - } - resLow = p00; - resHigh = p11; - } - }; - -private: - class IntermediateHull { - public: - Vertex* minXy; - Vertex* maxXy; - Vertex* minYx; - Vertex* maxYx; - - IntermediateHull() - : minXy(NULL) - , maxXy(NULL) - , minYx(NULL) - , maxYx(NULL) - { - } - - void print(); - }; - - enum Orientation { NONE, - CLOCKWISE, - COUNTER_CLOCKWISE }; - - template - class PoolArray { - private: - T* array; - int size; - - public: - PoolArray* next; - - PoolArray(int size) - : size(size) - , next(NULL) - { - array = (T*)btAlignedAlloc(sizeof(T) * size, 16); - } - - ~PoolArray() - { - btAlignedFree(array); - } - - T* init() - { - T* o = array; - for (int i = 0; i < size; i++, o++) { - o->next = (i + 1 < size) ? o + 1 : NULL; - } - return array; - } - }; - - template - class Pool { - private: - PoolArray* arrays; - PoolArray* nextArray; - T* freeObjects; - int arraySize; - - public: - Pool() - : arrays(NULL) - , nextArray(NULL) - , freeObjects(NULL) - , arraySize(256) - { - } - - ~Pool() - { - while (arrays) { - PoolArray* p = arrays; - arrays = p->next; - p->~PoolArray(); - btAlignedFree(p); - } - } - - void reset() - { - nextArray = arrays; - freeObjects = NULL; - } - - void setArraySize(int arraySize) - { - this->arraySize = arraySize; - } - - T* newObject() - { - T* o = freeObjects; - if (!o) { - PoolArray* p = nextArray; - if (p) { - nextArray = p->next; - } - else { - p = new (btAlignedAlloc(sizeof(PoolArray), 16)) PoolArray(arraySize); - p->next = arrays; - arrays = p; - } - o = p->init(); - } - freeObjects = o->next; - return new (o) T(); - }; - - void freeObject(T* object) - { - object->~T(); - object->next = freeObjects; - freeObjects = object; - } - }; - - btVector3 scaling; - btVector3 center; - Pool vertexPool; - Pool edgePool; - Pool facePool; - btAlignedObjectArray originalVertices; - int mergeStamp; - int minAxis; - int medAxis; - int maxAxis; - int usedEdgePairs; - int maxUsedEdgePairs; - - static Orientation getOrientation(const Edge* prev, const Edge* next, const Point32& s, const Point32& t); - Edge* findMaxAngle(bool ccw, const Vertex* start, const Point32& s, const Point64& rxs, const Point64& sxrxs, Rational64& minCot); - void findEdgeForCoplanarFaces(Vertex* c0, Vertex* c1, Edge*& e0, Edge*& e1, Vertex* stop0, Vertex* stop1); - - Edge* newEdgePair(Vertex* from, Vertex* to); - - void removeEdgePair(Edge* edge) - { - Edge* n = edge->next; - Edge* r = edge->reverse; - - btAssert(edge->target && r->target); - - if (n != edge) { - n->prev = edge->prev; - edge->prev->next = n; - r->target->edges = n; - } - else { - r->target->edges = NULL; - } - - n = r->next; - - if (n != r) { - n->prev = r->prev; - r->prev->next = n; - edge->target->edges = n; - } - else { - edge->target->edges = NULL; - } - - edgePool.freeObject(edge); - edgePool.freeObject(r); - usedEdgePairs--; - } - - void computeInternal(int start, int end, IntermediateHull& result); - - bool mergeProjection(IntermediateHull& h0, IntermediateHull& h1, Vertex*& c0, Vertex*& c1); - - void merge(IntermediateHull& h0, IntermediateHull& h1); - - btVector3 toBtVector(const Point32& v); - - btVector3 getBtNormal(Face* face); - - bool shiftFace(Face* face, btScalar amount, btAlignedObjectArray stack); - -public: - Vertex* vertexList; - - void compute(const void* coords, bool doubleCoords, int stride, int count); - - btVector3 getCoordinates(const Vertex* v); - - btScalar shrink(btScalar amount, btScalar clampAmount); -}; - -btConvexHullInternal::Int128 btConvexHullInternal::Int128::operator*(int64_t b) const -{ - bool negative = (int64_t)high < 0; - Int128 a = negative ? -*this : *this; - if (b < 0) { - negative = !negative; - b = -b; - } - Int128 result = mul(a.low, (uint64_t)b); - result.high += a.high * (uint64_t)b; - return negative ? -result : result; -} - -btConvexHullInternal::Int128 btConvexHullInternal::Int128::mul(int64_t a, int64_t b) -{ - Int128 result; - -#ifdef USE_X86_64_ASM - __asm__("imulq %[b]" - : "=a"(result.low), "=d"(result.high) - : "0"(a), [b] "r"(b) - : "cc"); - return result; - -#else - bool negative = a < 0; - if (negative) { - a = -a; - } - if (b < 0) { - negative = !negative; - b = -b; - } - DMul::mul((uint64_t)a, (uint64_t)b, result.low, result.high); - return negative ? -result : result; -#endif -} - -btConvexHullInternal::Int128 btConvexHullInternal::Int128::mul(uint64_t a, uint64_t b) -{ - Int128 result; - -#ifdef USE_X86_64_ASM - __asm__("mulq %[b]" - : "=a"(result.low), "=d"(result.high) - : "0"(a), [b] "r"(b) - : "cc"); - -#else - DMul::mul(a, b, result.low, result.high); -#endif - - return result; -} - -int btConvexHullInternal::Rational64::compare(const Rational64& b) const -{ - if (sign != b.sign) { - return sign - b.sign; - } - else if (sign == 0) { - return 0; - } - -// return (numerator * b.denominator > b.numerator * denominator) ? sign : (numerator * b.denominator < b.numerator * denominator) ? -sign : 0; - -#ifdef USE_X86_64_ASM - - int result; - int64_t tmp; - int64_t dummy; - __asm__("mulq %[bn]\n\t" - "movq %%rax, %[tmp]\n\t" - "movq %%rdx, %%rbx\n\t" - "movq %[tn], %%rax\n\t" - "mulq %[bd]\n\t" - "subq %[tmp], %%rax\n\t" - "sbbq %%rbx, %%rdx\n\t" // rdx:rax contains 128-bit-difference "numerator*b.denominator - b.numerator*denominator" - "setnsb %%bh\n\t" // bh=1 if difference is non-negative, bh=0 otherwise - "orq %%rdx, %%rax\n\t" - "setnzb %%bl\n\t" // bl=1 if difference if non-zero, bl=0 if it is zero - "decb %%bh\n\t" // now bx=0x0000 if difference is zero, 0xff01 if it is negative, 0x0001 if it is positive (i.e., same sign as difference) - "shll $16, %%ebx\n\t" // ebx has same sign as difference - : "=&b"(result), [tmp] "=&r"(tmp), "=a"(dummy) - : "a"(denominator), [bn] "g"(b.numerator), [tn] "g"(numerator), [bd] "g"(b.denominator) - : "%rdx", "cc"); - return result ? result ^ sign // if sign is +1, only bit 0 of result is inverted, which does not change the sign of result (and cannot result in zero) - // if sign is -1, all bits of result are inverted, which changes the sign of result (and again cannot result in zero) - : 0; - -#else - - return sign * Int128::mul(m_numerator, b.m_denominator).ucmp(Int128::mul(m_denominator, b.m_numerator)); - -#endif -} - -int btConvexHullInternal::Rational128::compare(const Rational128& b) const -{ - if (sign != b.sign) { - return sign - b.sign; - } - else if (sign == 0) { - return 0; - } - if (isInt64) { - return -b.compare(sign * (int64_t)numerator.low); - } - - Int128 nbdLow, nbdHigh, dbnLow, dbnHigh; - DMul::mul(numerator, b.denominator, nbdLow, nbdHigh); - DMul::mul(denominator, b.numerator, dbnLow, dbnHigh); - - int cmp = nbdHigh.ucmp(dbnHigh); - if (cmp) { - return cmp * sign; - } - return nbdLow.ucmp(dbnLow) * sign; -} - -int btConvexHullInternal::Rational128::compare(int64_t b) const -{ - if (isInt64) { - int64_t a = sign * (int64_t)numerator.low; - return (a > b) ? 1 : (a < b) ? -1 : 0; - } - if (b > 0) { - if (sign <= 0) { - return -1; - } - } - else if (b < 0) { - if (sign >= 0) { - return 1; - } - b = -b; - } - else { - return sign; - } - - return numerator.ucmp(denominator * b) * sign; -} - -btConvexHullInternal::Edge* btConvexHullInternal::newEdgePair(Vertex* from, Vertex* to) -{ - btAssert(from && to); - Edge* e = edgePool.newObject(); - Edge* r = edgePool.newObject(); - e->reverse = r; - r->reverse = e; - e->copy = mergeStamp; - r->copy = mergeStamp; - e->target = to; - r->target = from; - e->face = NULL; - r->face = NULL; - usedEdgePairs++; - if (usedEdgePairs > maxUsedEdgePairs) { - maxUsedEdgePairs = usedEdgePairs; - } - return e; -} - -bool btConvexHullInternal::mergeProjection(IntermediateHull& h0, IntermediateHull& h1, Vertex*& c0, Vertex*& c1) -{ - Vertex* v0 = h0.maxYx; - Vertex* v1 = h1.minYx; - if ((v0->point.x == v1->point.x) && (v0->point.y == v1->point.y)) { - btAssert(v0->point.z < v1->point.z); - Vertex* v1p = v1->prev; - if (v1p == v1) { - c0 = v0; - if (v1->edges) { - btAssert(v1->edges->next == v1->edges); - v1 = v1->edges->target; - btAssert(v1->edges->next == v1->edges); - } - c1 = v1; - return false; - } - Vertex* v1n = v1->next; - v1p->next = v1n; - v1n->prev = v1p; - if (v1 == h1.minXy) { - if ((v1n->point.x < v1p->point.x) || ((v1n->point.x == v1p->point.x) && (v1n->point.y < v1p->point.y))) { - h1.minXy = v1n; - } - else { - h1.minXy = v1p; - } - } - if (v1 == h1.maxXy) { - if ((v1n->point.x > v1p->point.x) || ((v1n->point.x == v1p->point.x) && (v1n->point.y > v1p->point.y))) { - h1.maxXy = v1n; - } - else { - h1.maxXy = v1p; - } - } - } - - v0 = h0.maxXy; - v1 = h1.maxXy; - Vertex* v00 = NULL; - Vertex* v10 = NULL; - int32_t sign = 1; - - for (int side = 0; side <= 1; side++) { - int32_t dx = (v1->point.x - v0->point.x) * sign; - if (dx > 0) { - while (true) { - int32_t dy = v1->point.y - v0->point.y; - - Vertex* w0 = side ? v0->next : v0->prev; - if (w0 != v0) { - int32_t dx0 = (w0->point.x - v0->point.x) * sign; - int32_t dy0 = w0->point.y - v0->point.y; - if ((dy0 <= 0) && ((dx0 == 0) || ((dx0 < 0) && (dy0 * dx <= dy * dx0)))) { - v0 = w0; - dx = (v1->point.x - v0->point.x) * sign; - continue; - } - } - - Vertex* w1 = side ? v1->next : v1->prev; - if (w1 != v1) { - int32_t dx1 = (w1->point.x - v1->point.x) * sign; - int32_t dy1 = w1->point.y - v1->point.y; - int32_t dxn = (w1->point.x - v0->point.x) * sign; - if ((dxn > 0) && (dy1 < 0) && ((dx1 == 0) || ((dx1 < 0) && (dy1 * dx < dy * dx1)))) { - v1 = w1; - dx = dxn; - continue; - } - } - - break; - } - } - else if (dx < 0) { - while (true) { - int32_t dy = v1->point.y - v0->point.y; - - Vertex* w1 = side ? v1->prev : v1->next; - if (w1 != v1) { - int32_t dx1 = (w1->point.x - v1->point.x) * sign; - int32_t dy1 = w1->point.y - v1->point.y; - if ((dy1 >= 0) && ((dx1 == 0) || ((dx1 < 0) && (dy1 * dx <= dy * dx1)))) { - v1 = w1; - dx = (v1->point.x - v0->point.x) * sign; - continue; - } - } - - Vertex* w0 = side ? v0->prev : v0->next; - if (w0 != v0) { - int32_t dx0 = (w0->point.x - v0->point.x) * sign; - int32_t dy0 = w0->point.y - v0->point.y; - int32_t dxn = (v1->point.x - w0->point.x) * sign; - if ((dxn < 0) && (dy0 > 0) && ((dx0 == 0) || ((dx0 < 0) && (dy0 * dx < dy * dx0)))) { - v0 = w0; - dx = dxn; - continue; - } - } - - break; - } - } - else { - int32_t x = v0->point.x; - int32_t y0 = v0->point.y; - Vertex* w0 = v0; - Vertex* t; - while (((t = side ? w0->next : w0->prev) != v0) && (t->point.x == x) && (t->point.y <= y0)) { - w0 = t; - y0 = t->point.y; - } - v0 = w0; - - int32_t y1 = v1->point.y; - Vertex* w1 = v1; - while (((t = side ? w1->prev : w1->next) != v1) && (t->point.x == x) && (t->point.y >= y1)) { - w1 = t; - y1 = t->point.y; - } - v1 = w1; - } - - if (side == 0) { - v00 = v0; - v10 = v1; - - v0 = h0.minXy; - v1 = h1.minXy; - sign = -1; - } - } - - v0->prev = v1; - v1->next = v0; - - v00->next = v10; - v10->prev = v00; - - if (h1.minXy->point.x < h0.minXy->point.x) { - h0.minXy = h1.minXy; - } - if (h1.maxXy->point.x >= h0.maxXy->point.x) { - h0.maxXy = h1.maxXy; - } - - h0.maxYx = h1.maxYx; - - c0 = v00; - c1 = v10; - - return true; -} - -void btConvexHullInternal::computeInternal(int start, int end, IntermediateHull& result) -{ - int n = end - start; - switch (n) { - case 0: - result.minXy = NULL; - result.maxXy = NULL; - result.minYx = NULL; - result.maxYx = NULL; - return; - case 2: { - Vertex* v = originalVertices[start]; - Vertex* w = v + 1; - if (v->point != w->point) { - int32_t dx = v->point.x - w->point.x; - int32_t dy = v->point.y - w->point.y; - - if ((dx == 0) && (dy == 0)) { - if (v->point.z > w->point.z) { - Vertex* t = w; - w = v; - v = t; - } - btAssert(v->point.z < w->point.z); - v->next = v; - v->prev = v; - result.minXy = v; - result.maxXy = v; - result.minYx = v; - result.maxYx = v; - } - else { - v->next = w; - v->prev = w; - w->next = v; - w->prev = v; - - if ((dx < 0) || ((dx == 0) && (dy < 0))) { - result.minXy = v; - result.maxXy = w; - } - else { - result.minXy = w; - result.maxXy = v; - } - - if ((dy < 0) || ((dy == 0) && (dx < 0))) { - result.minYx = v; - result.maxYx = w; - } - else { - result.minYx = w; - result.maxYx = v; - } - } - - Edge* e = newEdgePair(v, w); - e->link(e); - v->edges = e; - - e = e->reverse; - e->link(e); - w->edges = e; - - return; - } - } - // lint -fallthrough - case 1: { - Vertex* v = originalVertices[start]; - v->edges = NULL; - v->next = v; - v->prev = v; - - result.minXy = v; - result.maxXy = v; - result.minYx = v; - result.maxYx = v; - - return; - } - } - - int split0 = start + n / 2; - Point32 p = originalVertices[split0 - 1]->point; - int split1 = split0; - while ((split1 < end) && (originalVertices[split1]->point == p)) { - split1++; - } - computeInternal(start, split0, result); - IntermediateHull hull1; - computeInternal(split1, end, hull1); -#ifdef DEBUG_CONVEX_HULL - printf("\n\nMerge\n"); - result.print(); - hull1.print(); -#endif - merge(result, hull1); -#ifdef DEBUG_CONVEX_HULL - printf("\n Result\n"); - result.print(); -#endif -} - -#ifdef DEBUG_CONVEX_HULL -void btConvexHullInternal::IntermediateHull::print() -{ - printf(" Hull\n"); - for (Vertex* v = minXy; v;) { - printf(" "); - v->print(); - if (v == maxXy) { - printf(" maxXy"); - } - if (v == minYx) { - printf(" minYx"); - } - if (v == maxYx) { - printf(" maxYx"); - } - if (v->next->prev != v) { - printf(" Inconsistency"); - } - printf("\n"); - v = v->next; - if (v == minXy) { - break; - } - } - if (minXy) { - minXy->copy = (minXy->copy == -1) ? -2 : -1; - minXy->printGraph(); - } -} - -void btConvexHullInternal::Vertex::printGraph() -{ - print(); - printf("\nEdges\n"); - Edge* e = edges; - if (e) { - do { - e->print(); - printf("\n"); - e = e->next; - } while (e != edges); - do { - Vertex* v = e->target; - if (v->copy != copy) { - v->copy = copy; - v->printGraph(); - } - e = e->next; - } while (e != edges); - } -} -#endif - -btConvexHullInternal::Orientation btConvexHullInternal::getOrientation(const Edge* prev, const Edge* next, const Point32& s, const Point32& t) -{ - btAssert(prev->reverse->target == next->reverse->target); - if (prev->next == next) { - if (prev->prev == next) { - Point64 n = t.cross(s); - Point64 m = (*prev->target - *next->reverse->target).cross(*next->target - *next->reverse->target); - btAssert(!m.isZero()); - int64_t dot = n.dot(m); - btAssert(dot != 0); - return (dot > 0) ? COUNTER_CLOCKWISE : CLOCKWISE; - } - return COUNTER_CLOCKWISE; - } - else if (prev->prev == next) { - return CLOCKWISE; - } - else { - return NONE; - } -} - -btConvexHullInternal::Edge* btConvexHullInternal::findMaxAngle(bool ccw, const Vertex* start, const Point32& s, const Point64& rxs, const Point64& sxrxs, Rational64& minCot) -{ - Edge* minEdge = NULL; - -#ifdef DEBUG_CONVEX_HULL - printf("find max edge for %d\n", start->point.index); -#endif - Edge* e = start->edges; - if (e) { - do { - if (e->copy > mergeStamp) { - Point32 t = *e->target - *start; - Rational64 cot(t.dot(sxrxs), t.dot(rxs)); -#ifdef DEBUG_CONVEX_HULL - printf(" Angle is %f (%d) for ", (float)btAtan(cot.toScalar()), (int)cot.isNaN()); - e->print(); -#endif - if (cot.isNaN()) { - btAssert(ccw ? (t.dot(s) < 0) : (t.dot(s) > 0)); - } - else { - int cmp; - if (minEdge == NULL) { - minCot = cot; - minEdge = e; - } - else if ((cmp = cot.compare(minCot)) < 0) { - minCot = cot; - minEdge = e; - } - else if ((cmp == 0) && (ccw == (getOrientation(minEdge, e, s, t) == COUNTER_CLOCKWISE))) { - minEdge = e; - } - } -#ifdef DEBUG_CONVEX_HULL - printf("\n"); -#endif - } - e = e->next; - } while (e != start->edges); - } - return minEdge; -} - -void btConvexHullInternal::findEdgeForCoplanarFaces(Vertex* c0, Vertex* c1, Edge*& e0, Edge*& e1, Vertex* stop0, Vertex* stop1) -{ - Edge* start0 = e0; - Edge* start1 = e1; - Point32 et0 = start0 ? start0->target->point : c0->point; - Point32 et1 = start1 ? start1->target->point : c1->point; - Point32 s = c1->point - c0->point; - Point64 normal = ((start0 ? start0 : start1)->target->point - c0->point).cross(s); - int64_t dist = c0->point.dot(normal); - btAssert(!start1 || (start1->target->point.dot(normal) == dist)); - Point64 perp = s.cross(normal); - btAssert(!perp.isZero()); - -#ifdef DEBUG_CONVEX_HULL - printf(" Advancing %d %d (%p %p, %d %d)\n", c0->point.index, c1->point.index, start0, start1, start0 ? start0->target->point.index : -1, start1 ? start1->target->point.index : -1); -#endif - - int64_t maxDot0 = et0.dot(perp); - if (e0) { - while (e0->target != stop0) { - Edge* e = e0->reverse->prev; - if (e->target->point.dot(normal) < dist) { - break; - } - btAssert(e->target->point.dot(normal) == dist); - if (e->copy == mergeStamp) { - break; - } - int64_t dot = e->target->point.dot(perp); - if (dot <= maxDot0) { - break; - } - maxDot0 = dot; - e0 = e; - et0 = e->target->point; - } - } - - int64_t maxDot1 = et1.dot(perp); - if (e1) { - while (e1->target != stop1) { - Edge* e = e1->reverse->next; - if (e->target->point.dot(normal) < dist) { - break; - } - btAssert(e->target->point.dot(normal) == dist); - if (e->copy == mergeStamp) { - break; - } - int64_t dot = e->target->point.dot(perp); - if (dot <= maxDot1) { - break; - } - maxDot1 = dot; - e1 = e; - et1 = e->target->point; - } - } - -#ifdef DEBUG_CONVEX_HULL - printf(" Starting at %d %d\n", et0.index, et1.index); -#endif - - int64_t dx = maxDot1 - maxDot0; - if (dx > 0) { - while (true) { - int64_t dy = (et1 - et0).dot(s); - - if (e0 && (e0->target != stop0)) { - Edge* f0 = e0->next->reverse; - if (f0->copy > mergeStamp) { - int64_t dx0 = (f0->target->point - et0).dot(perp); - int64_t dy0 = (f0->target->point - et0).dot(s); - if ((dx0 == 0) ? (dy0 < 0) : ((dx0 < 0) && (Rational64(dy0, dx0).compare(Rational64(dy, dx)) >= 0))) { - et0 = f0->target->point; - dx = (et1 - et0).dot(perp); - e0 = (e0 == start0) ? NULL : f0; - continue; - } - } - } - - if (e1 && (e1->target != stop1)) { - Edge* f1 = e1->reverse->next; - if (f1->copy > mergeStamp) { - Point32 d1 = f1->target->point - et1; - if (d1.dot(normal) == 0) { - int64_t dx1 = d1.dot(perp); - int64_t dy1 = d1.dot(s); - int64_t dxn = (f1->target->point - et0).dot(perp); - if ((dxn > 0) && ((dx1 == 0) ? (dy1 < 0) : ((dx1 < 0) && (Rational64(dy1, dx1).compare(Rational64(dy, dx)) > 0)))) { - e1 = f1; - et1 = e1->target->point; - dx = dxn; - continue; - } - } - else { - btAssert((e1 == start1) && (d1.dot(normal) < 0)); - } - } - } - - break; - } - } - else if (dx < 0) { - while (true) { - int64_t dy = (et1 - et0).dot(s); - - if (e1 && (e1->target != stop1)) { - Edge* f1 = e1->prev->reverse; - if (f1->copy > mergeStamp) { - int64_t dx1 = (f1->target->point - et1).dot(perp); - int64_t dy1 = (f1->target->point - et1).dot(s); - if ((dx1 == 0) ? (dy1 > 0) : ((dx1 < 0) && (Rational64(dy1, dx1).compare(Rational64(dy, dx)) <= 0))) { - et1 = f1->target->point; - dx = (et1 - et0).dot(perp); - e1 = (e1 == start1) ? NULL : f1; - continue; - } - } - } - - if (e0 && (e0->target != stop0)) { - Edge* f0 = e0->reverse->prev; - if (f0->copy > mergeStamp) { - Point32 d0 = f0->target->point - et0; - if (d0.dot(normal) == 0) { - int64_t dx0 = d0.dot(perp); - int64_t dy0 = d0.dot(s); - int64_t dxn = (et1 - f0->target->point).dot(perp); - if ((dxn < 0) && ((dx0 == 0) ? (dy0 > 0) : ((dx0 < 0) && (Rational64(dy0, dx0).compare(Rational64(dy, dx)) < 0)))) { - e0 = f0; - et0 = e0->target->point; - dx = dxn; - continue; - } - } - else { - btAssert((e0 == start0) && (d0.dot(normal) < 0)); - } - } - } - - break; - } - } -#ifdef DEBUG_CONVEX_HULL - printf(" Advanced edges to %d %d\n", et0.index, et1.index); -#endif -} - -void btConvexHullInternal::merge(IntermediateHull& h0, IntermediateHull& h1) -{ - if (!h1.maxXy) { - return; - } - if (!h0.maxXy) { - h0 = h1; - return; - } - - mergeStamp--; - - Vertex* c0 = NULL; - Edge* toPrev0 = NULL; - Edge* firstNew0 = NULL; - Edge* pendingHead0 = NULL; - Edge* pendingTail0 = NULL; - Vertex* c1 = NULL; - Edge* toPrev1 = NULL; - Edge* firstNew1 = NULL; - Edge* pendingHead1 = NULL; - Edge* pendingTail1 = NULL; - Point32 prevPoint; - - if (mergeProjection(h0, h1, c0, c1)) { - Point32 s = *c1 - *c0; - Point64 normal = Point32(0, 0, -1).cross(s); - Point64 t = s.cross(normal); - btAssert(!t.isZero()); - - Edge* e = c0->edges; - Edge* start0 = NULL; - if (e) { - do { - int64_t dot = (*e->target - *c0).dot(normal); - btAssert(dot <= 0); - if ((dot == 0) && ((*e->target - *c0).dot(t) > 0)) { - if (!start0 || (getOrientation(start0, e, s, Point32(0, 0, -1)) == CLOCKWISE)) { - start0 = e; - } - } - e = e->next; - } while (e != c0->edges); - } - - e = c1->edges; - Edge* start1 = NULL; - if (e) { - do { - int64_t dot = (*e->target - *c1).dot(normal); - btAssert(dot <= 0); - if ((dot == 0) && ((*e->target - *c1).dot(t) > 0)) { - if (!start1 || (getOrientation(start1, e, s, Point32(0, 0, -1)) == COUNTER_CLOCKWISE)) { - start1 = e; - } - } - e = e->next; - } while (e != c1->edges); - } - - if (start0 || start1) { - findEdgeForCoplanarFaces(c0, c1, start0, start1, NULL, NULL); - if (start0) { - c0 = start0->target; - } - if (start1) { - c1 = start1->target; - } - } - - prevPoint = c1->point; - prevPoint.z++; - } - else { - prevPoint = c1->point; - prevPoint.x++; - } - - Vertex* first0 = c0; - Vertex* first1 = c1; - bool firstRun = true; - - while (true) { - Point32 s = *c1 - *c0; - Point32 r = prevPoint - c0->point; - Point64 rxs = r.cross(s); - Point64 sxrxs = s.cross(rxs); - -#ifdef DEBUG_CONVEX_HULL - printf("\n Checking %d %d\n", c0->point.index, c1->point.index); -#endif - Rational64 minCot0(0, 0); - Edge* min0 = findMaxAngle(false, c0, s, rxs, sxrxs, minCot0); - Rational64 minCot1(0, 0); - Edge* min1 = findMaxAngle(true, c1, s, rxs, sxrxs, minCot1); - if (!min0 && !min1) { - Edge* e = newEdgePair(c0, c1); - e->link(e); - c0->edges = e; - - e = e->reverse; - e->link(e); - c1->edges = e; - return; - } - else { - int cmp = !min0 ? 1 : !min1 ? -1 : minCot0.compare(minCot1); -#ifdef DEBUG_CONVEX_HULL - printf(" -> Result %d\n", cmp); -#endif - if (firstRun || ((cmp >= 0) ? !minCot1.isNegativeInfinity() : !minCot0.isNegativeInfinity())) { - Edge* e = newEdgePair(c0, c1); - if (pendingTail0) { - pendingTail0->prev = e; - } - else { - pendingHead0 = e; - } - e->next = pendingTail0; - pendingTail0 = e; - - e = e->reverse; - if (pendingTail1) { - pendingTail1->next = e; - } - else { - pendingHead1 = e; - } - e->prev = pendingTail1; - pendingTail1 = e; - } - - Edge* e0 = min0; - Edge* e1 = min1; - -#ifdef DEBUG_CONVEX_HULL - printf(" Found min edges to %d %d\n", e0 ? e0->target->point.index : -1, e1 ? e1->target->point.index : -1); -#endif - - if (cmp == 0) { - findEdgeForCoplanarFaces(c0, c1, e0, e1, NULL, NULL); - } - - if ((cmp >= 0) && e1) { - if (toPrev1) { - for (Edge *e = toPrev1->next, *n = NULL; e != min1; e = n) { - n = e->next; - removeEdgePair(e); - } - } - - if (pendingTail1) { - if (toPrev1) { - toPrev1->link(pendingHead1); - } - else { - min1->prev->link(pendingHead1); - firstNew1 = pendingHead1; - } - pendingTail1->link(min1); - pendingHead1 = NULL; - pendingTail1 = NULL; - } - else if (!toPrev1) { - firstNew1 = min1; - } - - prevPoint = c1->point; - c1 = e1->target; - toPrev1 = e1->reverse; - } - - if ((cmp <= 0) && e0) { - if (toPrev0) { - for (Edge *e = toPrev0->prev, *n = NULL; e != min0; e = n) { - n = e->prev; - removeEdgePair(e); - } - } - - if (pendingTail0) { - if (toPrev0) { - pendingHead0->link(toPrev0); - } - else { - pendingHead0->link(min0->next); - firstNew0 = pendingHead0; - } - min0->link(pendingTail0); - pendingHead0 = NULL; - pendingTail0 = NULL; - } - else if (!toPrev0) { - firstNew0 = min0; - } - - prevPoint = c0->point; - c0 = e0->target; - toPrev0 = e0->reverse; - } - } - - if ((c0 == first0) && (c1 == first1)) { - if (toPrev0 == NULL) { - pendingHead0->link(pendingTail0); - c0->edges = pendingTail0; - } - else { - for (Edge *e = toPrev0->prev, *n = NULL; e != firstNew0; e = n) { - n = e->prev; - removeEdgePair(e); - } - if (pendingTail0) { - pendingHead0->link(toPrev0); - firstNew0->link(pendingTail0); - } - } - - if (toPrev1 == NULL) { - pendingTail1->link(pendingHead1); - c1->edges = pendingTail1; - } - else { - for (Edge *e = toPrev1->next, *n = NULL; e != firstNew1; e = n) { - n = e->next; - removeEdgePair(e); - } - if (pendingTail1) { - toPrev1->link(pendingHead1); - pendingTail1->link(firstNew1); - } - } - - return; - } - - firstRun = false; - } -} - -static bool pointCmp(const btConvexHullInternal::Point32& p, const btConvexHullInternal::Point32& q) -{ - return (p.y < q.y) || ((p.y == q.y) && ((p.x < q.x) || ((p.x == q.x) && (p.z < q.z)))); -} - -void btConvexHullInternal::compute(const void* coords, bool doubleCoords, int stride, int count) -{ - btVector3 min(btScalar(1e30), btScalar(1e30), btScalar(1e30)), max(btScalar(-1e30), btScalar(-1e30), btScalar(-1e30)); - const char* ptr = (const char*)coords; - if (doubleCoords) { - for (int i = 0; i < count; i++) { - const double* v = (const double*)ptr; - btVector3 p((btScalar)v[0], (btScalar)v[1], (btScalar)v[2]); - ptr += stride; - min.setMin(p); - max.setMax(p); - } - } - else { - for (int i = 0; i < count; i++) { - const float* v = (const float*)ptr; - btVector3 p(v[0], v[1], v[2]); - ptr += stride; - min.setMin(p); - max.setMax(p); - } - } - - btVector3 s = max - min; - maxAxis = s.maxAxis(); - minAxis = s.minAxis(); - if (minAxis == maxAxis) { - minAxis = (maxAxis + 1) % 3; - } - medAxis = 3 - maxAxis - minAxis; - - s /= btScalar(10216); - if (((medAxis + 1) % 3) != maxAxis) { - s *= -1; - } - scaling = s; - - if (s[0] != 0) { - s[0] = btScalar(1) / s[0]; - } - if (s[1] != 0) { - s[1] = btScalar(1) / s[1]; - } - if (s[2] != 0) { - s[2] = btScalar(1) / s[2]; - } - - center = (min + max) * btScalar(0.5); - - btAlignedObjectArray points; - points.resize(count); - ptr = (const char*)coords; - if (doubleCoords) { - for (int i = 0; i < count; i++) { - const double* v = (const double*)ptr; - btVector3 p((btScalar)v[0], (btScalar)v[1], (btScalar)v[2]); - ptr += stride; - p = (p - center) * s; - points[i].x = (int32_t)p[medAxis]; - points[i].y = (int32_t)p[maxAxis]; - points[i].z = (int32_t)p[minAxis]; - points[i].index = i; - } - } - else { - for (int i = 0; i < count; i++) { - const float* v = (const float*)ptr; - btVector3 p(v[0], v[1], v[2]); - ptr += stride; - p = (p - center) * s; - points[i].x = (int32_t)p[medAxis]; - points[i].y = (int32_t)p[maxAxis]; - points[i].z = (int32_t)p[minAxis]; - points[i].index = i; - } - } - points.quickSort(pointCmp); - - vertexPool.reset(); - vertexPool.setArraySize(count); - originalVertices.resize(count); - for (int i = 0; i < count; i++) { - Vertex* v = vertexPool.newObject(); - v->edges = NULL; - v->point = points[i]; - v->copy = -1; - originalVertices[i] = v; - } - - points.clear(); - - edgePool.reset(); - edgePool.setArraySize(6 * count); - - usedEdgePairs = 0; - maxUsedEdgePairs = 0; - - mergeStamp = -3; - - IntermediateHull hull; - computeInternal(0, count, hull); - vertexList = hull.minXy; -#ifdef DEBUG_CONVEX_HULL - printf("max. edges %d (3v = %d)", maxUsedEdgePairs, 3 * count); -#endif -} - -btVector3 btConvexHullInternal::toBtVector(const Point32& v) -{ - btVector3 p; - p[medAxis] = btScalar(v.x); - p[maxAxis] = btScalar(v.y); - p[minAxis] = btScalar(v.z); - return p * scaling; -} - -btVector3 btConvexHullInternal::getBtNormal(Face* face) -{ - return toBtVector(face->dir0).cross(toBtVector(face->dir1)).normalized(); -} - -btVector3 btConvexHullInternal::getCoordinates(const Vertex* v) -{ - btVector3 p; - p[medAxis] = v->xvalue(); - p[maxAxis] = v->yvalue(); - p[minAxis] = v->zvalue(); - return p * scaling + center; -} - -btScalar btConvexHullInternal::shrink(btScalar amount, btScalar clampAmount) -{ - if (!vertexList) { - return 0; - } - int stamp = --mergeStamp; - btAlignedObjectArray stack; - vertexList->copy = stamp; - stack.push_back(vertexList); - btAlignedObjectArray faces; - - Point32 ref = vertexList->point; - Int128 hullCenterX(0, 0); - Int128 hullCenterY(0, 0); - Int128 hullCenterZ(0, 0); - Int128 volume(0, 0); - - while (stack.size() > 0) { - Vertex* v = stack[stack.size() - 1]; - stack.pop_back(); - Edge* e = v->edges; - if (e) { - do { - if (e->target->copy != stamp) { - e->target->copy = stamp; - stack.push_back(e->target); - } - if (e->copy != stamp) { - Face* face = facePool.newObject(); - face->init(e->target, e->reverse->prev->target, v); - faces.push_back(face); - Edge* f = e; - - Vertex* a = NULL; - Vertex* b = NULL; - do { - if (a && b) { - int64_t vol = (v->point - ref).dot((a->point - ref).cross(b->point - ref)); - btAssert(vol >= 0); - Point32 c = v->point + a->point + b->point + ref; - hullCenterX += vol * c.x; - hullCenterY += vol * c.y; - hullCenterZ += vol * c.z; - volume += vol; - } - - btAssert(f->copy != stamp); - f->copy = stamp; - f->face = face; - - a = b; - b = f->target; - - f = f->reverse->prev; - } while (f != e); - } - e = e->next; - } while (e != v->edges); - } - } - - if (volume.getSign() <= 0) { - return 0; - } - - btVector3 hullCenter; - hullCenter[medAxis] = hullCenterX.toScalar(); - hullCenter[maxAxis] = hullCenterY.toScalar(); - hullCenter[minAxis] = hullCenterZ.toScalar(); - hullCenter /= 4 * volume.toScalar(); - hullCenter *= scaling; - - int faceCount = faces.size(); - - if (clampAmount > 0) { - btScalar minDist = SIMD_INFINITY; - for (int i = 0; i < faceCount; i++) { - btVector3 normal = getBtNormal(faces[i]); - btScalar dist = normal.dot(toBtVector(faces[i]->origin) - hullCenter); - if (dist < minDist) { - minDist = dist; - } - } - - if (minDist <= 0) { - return 0; - } - - amount = btMin(amount, minDist * clampAmount); - } - - unsigned int seed = 243703; - for (int i = 0; i < faceCount; i++, seed = 1664525 * seed + 1013904223) { - btSwap(faces[i], faces[seed % faceCount]); - } - - for (int i = 0; i < faceCount; i++) { - if (!shiftFace(faces[i], amount, stack)) { - return -amount; - } - } - - return amount; -} - -bool btConvexHullInternal::shiftFace(Face* face, btScalar amount, btAlignedObjectArray stack) -{ - btVector3 origShift = getBtNormal(face) * -amount; - if (scaling[0] != 0) { - origShift[0] /= scaling[0]; - } - if (scaling[1] != 0) { - origShift[1] /= scaling[1]; - } - if (scaling[2] != 0) { - origShift[2] /= scaling[2]; - } - Point32 shift((int32_t)origShift[medAxis], (int32_t)origShift[maxAxis], (int32_t)origShift[minAxis]); - if (shift.isZero()) { - return true; - } - Point64 normal = face->getNormal(); -#ifdef DEBUG_CONVEX_HULL - printf("\nShrinking face (%d %d %d) (%d %d %d) (%d %d %d) by (%d %d %d)\n", - face->origin.x, face->origin.y, face->origin.z, face->dir0.x, face->dir0.y, face->dir0.z, face->dir1.x, face->dir1.y, face->dir1.z, shift.x, shift.y, shift.z); -#endif - int64_t origDot = face->origin.dot(normal); - Point32 shiftedOrigin = face->origin + shift; - int64_t shiftedDot = shiftedOrigin.dot(normal); - btAssert(shiftedDot <= origDot); - if (shiftedDot >= origDot) { - return false; - } - - Edge* intersection = NULL; - - Edge* startEdge = face->nearbyVertex->edges; -#ifdef DEBUG_CONVEX_HULL - printf("Start edge is "); - startEdge->print(); - printf(", normal is (%lld %lld %lld), shifted dot is %lld\n", normal.x, normal.y, normal.z, shiftedDot); -#endif - Rational128 optDot = face->nearbyVertex->dot(normal); - int cmp = optDot.compare(shiftedDot); -#ifdef SHOW_ITERATIONS - int n = 0; -#endif - if (cmp >= 0) { - Edge* e = startEdge; - do { -#ifdef SHOW_ITERATIONS - n++; -#endif - Rational128 dot = e->target->dot(normal); - btAssert(dot.compare(origDot) <= 0); -#ifdef DEBUG_CONVEX_HULL - printf("Moving downwards, edge is "); - e->print(); - printf(", dot is %f (%f %lld)\n", (float)dot.toScalar(), (float)optDot.toScalar(), shiftedDot); -#endif - if (dot.compare(optDot) < 0) { - int c = dot.compare(shiftedDot); - optDot = dot; - e = e->reverse; - startEdge = e; - if (c < 0) { - intersection = e; - break; - } - cmp = c; - } - e = e->prev; - } while (e != startEdge); - - if (!intersection) { - return false; - } - } - else { - Edge* e = startEdge; - do { -#ifdef SHOW_ITERATIONS - n++; -#endif - Rational128 dot = e->target->dot(normal); - btAssert(dot.compare(origDot) <= 0); -#ifdef DEBUG_CONVEX_HULL - printf("Moving upwards, edge is "); - e->print(); - printf(", dot is %f (%f %lld)\n", (float)dot.toScalar(), (float)optDot.toScalar(), shiftedDot); -#endif - if (dot.compare(optDot) > 0) { - cmp = dot.compare(shiftedDot); - if (cmp >= 0) { - intersection = e; - break; - } - optDot = dot; - e = e->reverse; - startEdge = e; - } - e = e->prev; - } while (e != startEdge); - - if (!intersection) { - return true; - } - } - -#ifdef SHOW_ITERATIONS - printf("Needed %d iterations to find initial intersection\n", n); -#endif - - if (cmp == 0) { - Edge* e = intersection->reverse->next; -#ifdef SHOW_ITERATIONS - n = 0; -#endif - while (e->target->dot(normal).compare(shiftedDot) <= 0) { -#ifdef SHOW_ITERATIONS - n++; -#endif - e = e->next; - if (e == intersection->reverse) { - return true; - } -#ifdef DEBUG_CONVEX_HULL - printf("Checking for outwards edge, current edge is "); - e->print(); - printf("\n"); -#endif - } -#ifdef SHOW_ITERATIONS - printf("Needed %d iterations to check for complete containment\n", n); -#endif - } - - Edge* firstIntersection = NULL; - Edge* faceEdge = NULL; - Edge* firstFaceEdge = NULL; - -#ifdef SHOW_ITERATIONS - int m = 0; -#endif - while (true) { -#ifdef SHOW_ITERATIONS - m++; -#endif -#ifdef DEBUG_CONVEX_HULL - printf("Intersecting edge is "); - intersection->print(); - printf("\n"); -#endif - if (cmp == 0) { - Edge* e = intersection->reverse->next; - startEdge = e; -#ifdef SHOW_ITERATIONS - n = 0; -#endif - while (true) { -#ifdef SHOW_ITERATIONS - n++; -#endif - if (e->target->dot(normal).compare(shiftedDot) >= 0) { - break; - } - intersection = e->reverse; - e = e->next; - if (e == startEdge) { - return true; - } - } -#ifdef SHOW_ITERATIONS - printf("Needed %d iterations to advance intersection\n", n); -#endif - } - -#ifdef DEBUG_CONVEX_HULL - printf("Advanced intersecting edge to "); - intersection->print(); - printf(", cmp = %d\n", cmp); -#endif - - if (!firstIntersection) { - firstIntersection = intersection; - } - else if (intersection == firstIntersection) { - break; - } - - int prevCmp = cmp; - Edge* prevIntersection = intersection; - Edge* prevFaceEdge = faceEdge; - - Edge* e = intersection->reverse; -#ifdef SHOW_ITERATIONS - n = 0; -#endif - while (true) { -#ifdef SHOW_ITERATIONS - n++; -#endif - e = e->reverse->prev; - btAssert(e != intersection->reverse); - cmp = e->target->dot(normal).compare(shiftedDot); -#ifdef DEBUG_CONVEX_HULL - printf("Testing edge "); - e->print(); - printf(" -> cmp = %d\n", cmp); -#endif - if (cmp >= 0) { - intersection = e; - break; - } - } -#ifdef SHOW_ITERATIONS - printf("Needed %d iterations to find other intersection of face\n", n); -#endif - - if (cmp > 0) { - Vertex* removed = intersection->target; - e = intersection->reverse; - if (e->prev == e) { - removed->edges = NULL; - } - else { - removed->edges = e->prev; - e->prev->link(e->next); - e->link(e); - } -#ifdef DEBUG_CONVEX_HULL - printf("1: Removed part contains (%d %d %d)\n", removed->point.x, removed->point.y, removed->point.z); -#endif - - Point64 n0 = intersection->face->getNormal(); - Point64 n1 = intersection->reverse->face->getNormal(); - int64_t m00 = face->dir0.dot(n0); - int64_t m01 = face->dir1.dot(n0); - int64_t m10 = face->dir0.dot(n1); - int64_t m11 = face->dir1.dot(n1); - int64_t r0 = (intersection->face->origin - shiftedOrigin).dot(n0); - int64_t r1 = (intersection->reverse->face->origin - shiftedOrigin).dot(n1); - Int128 det = Int128::mul(m00, m11) - Int128::mul(m01, m10); - btAssert(det.getSign() != 0); - Vertex* v = vertexPool.newObject(); - v->point.index = -1; - v->copy = -1; - v->point128 = PointR128(Int128::mul(face->dir0.x * r0, m11) - Int128::mul(face->dir0.x * r1, m01) - + Int128::mul(face->dir1.x * r1, m00) - Int128::mul(face->dir1.x * r0, m10) + det * shiftedOrigin.x, - Int128::mul(face->dir0.y * r0, m11) - Int128::mul(face->dir0.y * r1, m01) - + Int128::mul(face->dir1.y * r1, m00) - Int128::mul(face->dir1.y * r0, m10) + det * shiftedOrigin.y, - Int128::mul(face->dir0.z * r0, m11) - Int128::mul(face->dir0.z * r1, m01) - + Int128::mul(face->dir1.z * r1, m00) - Int128::mul(face->dir1.z * r0, m10) + det * shiftedOrigin.z, - det); - v->point.x = (int32_t)v->point128.xvalue(); - v->point.y = (int32_t)v->point128.yvalue(); - v->point.z = (int32_t)v->point128.zvalue(); - intersection->target = v; - v->edges = e; - - stack.push_back(v); - stack.push_back(removed); - stack.push_back(NULL); - } - - if (cmp || prevCmp || (prevIntersection->reverse->next->target != intersection->target)) { - faceEdge = newEdgePair(prevIntersection->target, intersection->target); - if (prevCmp == 0) { - faceEdge->link(prevIntersection->reverse->next); - } - if ((prevCmp == 0) || prevFaceEdge) { - prevIntersection->reverse->link(faceEdge); - } - if (cmp == 0) { - intersection->reverse->prev->link(faceEdge->reverse); - } - faceEdge->reverse->link(intersection->reverse); - } - else { - faceEdge = prevIntersection->reverse->next; - } - - if (prevFaceEdge) { - if (prevCmp > 0) { - faceEdge->link(prevFaceEdge->reverse); - } - else if (faceEdge != prevFaceEdge->reverse) { - stack.push_back(prevFaceEdge->target); - while (faceEdge->next != prevFaceEdge->reverse) { - Vertex* removed = faceEdge->next->target; - removeEdgePair(faceEdge->next); - stack.push_back(removed); -#ifdef DEBUG_CONVEX_HULL - printf("2: Removed part contains (%d %d %d)\n", removed->point.x, removed->point.y, removed->point.z); -#endif - } - stack.push_back(NULL); - } - } - faceEdge->face = face; - faceEdge->reverse->face = intersection->face; - - if (!firstFaceEdge) { - firstFaceEdge = faceEdge; - } - } -#ifdef SHOW_ITERATIONS - printf("Needed %d iterations to process all intersections\n", m); -#endif - - if (cmp > 0) { - firstFaceEdge->reverse->target = faceEdge->target; - firstIntersection->reverse->link(firstFaceEdge); - firstFaceEdge->link(faceEdge->reverse); - } - else if (firstFaceEdge != faceEdge->reverse) { - stack.push_back(faceEdge->target); - while (firstFaceEdge->next != faceEdge->reverse) { - Vertex* removed = firstFaceEdge->next->target; - removeEdgePair(firstFaceEdge->next); - stack.push_back(removed); -#ifdef DEBUG_CONVEX_HULL - printf("3: Removed part contains (%d %d %d)\n", removed->point.x, removed->point.y, removed->point.z); -#endif - } - stack.push_back(NULL); - } - - btAssert(stack.size() > 0); - vertexList = stack[0]; - -#ifdef DEBUG_CONVEX_HULL - printf("Removing part\n"); -#endif -#ifdef SHOW_ITERATIONS - n = 0; -#endif - int pos = 0; - while (pos < stack.size()) { - int end = stack.size(); - while (pos < end) { - Vertex* kept = stack[pos++]; -#ifdef DEBUG_CONVEX_HULL - kept->print(); -#endif - bool deeper = false; - Vertex* removed; - while ((removed = stack[pos++]) != NULL) { -#ifdef SHOW_ITERATIONS - n++; -#endif - kept->receiveNearbyFaces(removed); - while (removed->edges) { - if (!deeper) { - deeper = true; - stack.push_back(kept); - } - stack.push_back(removed->edges->target); - removeEdgePair(removed->edges); - } - } - if (deeper) { - stack.push_back(NULL); - } - } - } -#ifdef SHOW_ITERATIONS - printf("Needed %d iterations to remove part\n", n); -#endif - - stack.resize(0); - face->origin = shiftedOrigin; - - return true; -} - -static int getVertexCopy(btConvexHullInternal::Vertex* vertex, btAlignedObjectArray& vertices) -{ - int index = vertex->copy; - if (index < 0) { - index = vertices.size(); - vertex->copy = index; - vertices.push_back(vertex); -#ifdef DEBUG_CONVEX_HULL - printf("Vertex %d gets index *%d\n", vertex->point.index, index); -#endif - } - return index; -} - -btScalar btConvexHullComputer::compute(const void* coords, bool doubleCoords, int stride, int count, btScalar shrink, btScalar shrinkClamp) -{ - if (count <= 0) { - vertices.clear(); - edges.clear(); - faces.clear(); - return 0; - } - - btConvexHullInternal hull; - hull.compute(coords, doubleCoords, stride, count); - - btScalar shift = 0; - if ((shrink > 0) && ((shift = hull.shrink(shrink, shrinkClamp)) < 0)) { - vertices.clear(); - edges.clear(); - faces.clear(); - return shift; - } - - vertices.resize(0); - edges.resize(0); - faces.resize(0); - - btAlignedObjectArray oldVertices; - getVertexCopy(hull.vertexList, oldVertices); - int copied = 0; - while (copied < oldVertices.size()) { - btConvexHullInternal::Vertex* v = oldVertices[copied]; - vertices.push_back(hull.getCoordinates(v)); - btConvexHullInternal::Edge* firstEdge = v->edges; - if (firstEdge) { - int firstCopy = -1; - int prevCopy = -1; - btConvexHullInternal::Edge* e = firstEdge; - do { - if (e->copy < 0) { - int s = edges.size(); - edges.push_back(Edge()); - edges.push_back(Edge()); - Edge* c = &edges[s]; - Edge* r = &edges[s + 1]; - e->copy = s; - e->reverse->copy = s + 1; - c->reverse = 1; - r->reverse = -1; - c->targetVertex = getVertexCopy(e->target, oldVertices); - r->targetVertex = copied; -#ifdef DEBUG_CONVEX_HULL - printf(" CREATE: Vertex *%d has edge to *%d\n", copied, c->getTargetVertex()); -#endif - } - if (prevCopy >= 0) { - edges[e->copy].next = prevCopy - e->copy; - } - else { - firstCopy = e->copy; - } - prevCopy = e->copy; - e = e->next; - } while (e != firstEdge); - edges[firstCopy].next = prevCopy - firstCopy; - } - copied++; - } - - for (int i = 0; i < copied; i++) { - btConvexHullInternal::Vertex* v = oldVertices[i]; - btConvexHullInternal::Edge* firstEdge = v->edges; - if (firstEdge) { - btConvexHullInternal::Edge* e = firstEdge; - do { - if (e->copy >= 0) { -#ifdef DEBUG_CONVEX_HULL - printf("Vertex *%d has edge to *%d\n", i, edges[e->copy].getTargetVertex()); -#endif - faces.push_back(e->copy); - btConvexHullInternal::Edge* f = e; - do { -#ifdef DEBUG_CONVEX_HULL - printf(" Face *%d\n", edges[f->copy].getTargetVertex()); -#endif - f->copy = -1; - f = f->reverse->prev; - } while (f != e); - } - e = e->next; - } while (e != firstEdge); - } - } - - return shift; -} diff --git a/extern/bullet/src/Extras/VHACD/src/premake4.lua b/extern/bullet/src/Extras/VHACD/src/premake4.lua deleted file mode 100644 index 10083cffe295..000000000000 --- a/extern/bullet/src/Extras/VHACD/src/premake4.lua +++ /dev/null @@ -1,13 +0,0 @@ - project "vhacd" - - kind "StaticLib" - if os.is("Linux") then - buildoptions{"-fPIC"} - end - includedirs { - "../inc","../public", - } - files { - "*.cpp", - "*.h" - } diff --git a/extern/bullet/src/Extras/VHACD/src/vhacdICHull.cpp b/extern/bullet/src/Extras/VHACD/src/vhacdICHull.cpp deleted file mode 100644 index ac3c67924290..000000000000 --- a/extern/bullet/src/Extras/VHACD/src/vhacdICHull.cpp +++ /dev/null @@ -1,725 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) - All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#include "Extras/VHACD/inc/vhacdICHull.h" -#include -namespace VHACD { -const double ICHull::sc_eps = 1.0e-15; -const int ICHull::sc_dummyIndex = std::numeric_limits::max(); -ICHull::ICHull() -{ - m_isFlat = false; -} -bool ICHull::AddPoints(const Vec3* points, size_t nPoints) -{ - if (!points) { - return false; - } - CircularListElement* vertex = NULL; - for (size_t i = 0; i < nPoints; i++) { - vertex = m_mesh.AddVertex(); - vertex->GetData().m_pos.X() = points[i].X(); - vertex->GetData().m_pos.Y() = points[i].Y(); - vertex->GetData().m_pos.Z() = points[i].Z(); - vertex->GetData().m_name = static_cast(i); - } - return true; -} -bool ICHull::AddPoint(const Vec3& point, int id) -{ - if (AddPoints(&point, 1)) { - m_mesh.m_vertices.GetData().m_name = id; - return true; - } - return false; -} - -ICHullError ICHull::Process() -{ - unsigned int addedPoints = 0; - if (m_mesh.GetNVertices() < 3) { - return ICHullErrorNotEnoughPoints; - } - if (m_mesh.GetNVertices() == 3) { - m_isFlat = true; - CircularListElement* t1 = m_mesh.AddTriangle(); - CircularListElement* t2 = m_mesh.AddTriangle(); - CircularListElement* v0 = m_mesh.m_vertices.GetHead(); - CircularListElement* v1 = v0->GetNext(); - CircularListElement* v2 = v1->GetNext(); - // Compute the normal to the plane - Vec3 p0 = v0->GetData().m_pos; - Vec3 p1 = v1->GetData().m_pos; - Vec3 p2 = v2->GetData().m_pos; - m_normal = (p1 - p0) ^ (p2 - p0); - m_normal.Normalize(); - t1->GetData().m_vertices[0] = v0; - t1->GetData().m_vertices[1] = v1; - t1->GetData().m_vertices[2] = v2; - t2->GetData().m_vertices[0] = v1; - t2->GetData().m_vertices[1] = v2; - t2->GetData().m_vertices[2] = v2; - return ICHullErrorOK; - } - if (m_isFlat) { - m_mesh.m_edges.Clear(); - m_mesh.m_triangles.Clear(); - m_isFlat = false; - } - if (m_mesh.GetNTriangles() == 0) // we have to create the first polyhedron - { - ICHullError res = DoubleTriangle(); - if (res != ICHullErrorOK) { - return res; - } - else { - addedPoints += 3; - } - } - CircularList& vertices = m_mesh.GetVertices(); - // go to the first added and not processed vertex - while (!(vertices.GetHead()->GetPrev()->GetData().m_tag)) { - vertices.Prev(); - } - while (!vertices.GetData().m_tag) // not processed - { - vertices.GetData().m_tag = true; - if (ProcessPoint()) { - addedPoints++; - CleanUp(addedPoints); - vertices.Next(); - if (!GetMesh().CheckConsistancy()) { - size_t nV = m_mesh.GetNVertices(); - CircularList& vertices = m_mesh.GetVertices(); - for (size_t v = 0; v < nV; ++v) { - if (vertices.GetData().m_name == sc_dummyIndex) { - vertices.Delete(); - break; - } - vertices.Next(); - } - return ICHullErrorInconsistent; - } - } - } - if (m_isFlat) { - SArray*> trianglesToDuplicate; - size_t nT = m_mesh.GetNTriangles(); - for (size_t f = 0; f < nT; f++) { - TMMTriangle& currentTriangle = m_mesh.m_triangles.GetHead()->GetData(); - if (currentTriangle.m_vertices[0]->GetData().m_name == sc_dummyIndex || currentTriangle.m_vertices[1]->GetData().m_name == sc_dummyIndex || currentTriangle.m_vertices[2]->GetData().m_name == sc_dummyIndex) { - m_trianglesToDelete.PushBack(m_mesh.m_triangles.GetHead()); - for (int k = 0; k < 3; k++) { - for (int h = 0; h < 2; h++) { - if (currentTriangle.m_edges[k]->GetData().m_triangles[h] == m_mesh.m_triangles.GetHead()) { - currentTriangle.m_edges[k]->GetData().m_triangles[h] = 0; - break; - } - } - } - } - else { - trianglesToDuplicate.PushBack(m_mesh.m_triangles.GetHead()); - } - m_mesh.m_triangles.Next(); - } - size_t nE = m_mesh.GetNEdges(); - for (size_t e = 0; e < nE; e++) { - TMMEdge& currentEdge = m_mesh.m_edges.GetHead()->GetData(); - if (currentEdge.m_triangles[0] == 0 && currentEdge.m_triangles[1] == 0) { - m_edgesToDelete.PushBack(m_mesh.m_edges.GetHead()); - } - m_mesh.m_edges.Next(); - } - size_t nV = m_mesh.GetNVertices(); - CircularList& vertices = m_mesh.GetVertices(); - for (size_t v = 0; v < nV; ++v) { - if (vertices.GetData().m_name == sc_dummyIndex) { - vertices.Delete(); - } - else { - vertices.GetData().m_tag = false; - vertices.Next(); - } - } - CleanEdges(); - CleanTriangles(); - CircularListElement* newTriangle; - for (size_t t = 0; t < trianglesToDuplicate.Size(); t++) { - newTriangle = m_mesh.AddTriangle(); - newTriangle->GetData().m_vertices[0] = trianglesToDuplicate[t]->GetData().m_vertices[1]; - newTriangle->GetData().m_vertices[1] = trianglesToDuplicate[t]->GetData().m_vertices[0]; - newTriangle->GetData().m_vertices[2] = trianglesToDuplicate[t]->GetData().m_vertices[2]; - } - } - return ICHullErrorOK; -} -ICHullError ICHull::Process(const unsigned int nPointsCH, - const double minVolume) -{ - unsigned int addedPoints = 0; - if (nPointsCH < 3 || m_mesh.GetNVertices() < 3) { - return ICHullErrorNotEnoughPoints; - } - if (m_mesh.GetNVertices() == 3) { - m_isFlat = true; - CircularListElement* t1 = m_mesh.AddTriangle(); - CircularListElement* t2 = m_mesh.AddTriangle(); - CircularListElement* v0 = m_mesh.m_vertices.GetHead(); - CircularListElement* v1 = v0->GetNext(); - CircularListElement* v2 = v1->GetNext(); - // Compute the normal to the plane - Vec3 p0 = v0->GetData().m_pos; - Vec3 p1 = v1->GetData().m_pos; - Vec3 p2 = v2->GetData().m_pos; - m_normal = (p1 - p0) ^ (p2 - p0); - m_normal.Normalize(); - t1->GetData().m_vertices[0] = v0; - t1->GetData().m_vertices[1] = v1; - t1->GetData().m_vertices[2] = v2; - t2->GetData().m_vertices[0] = v1; - t2->GetData().m_vertices[1] = v0; - t2->GetData().m_vertices[2] = v2; - return ICHullErrorOK; - } - - if (m_isFlat) { - m_mesh.m_triangles.Clear(); - m_mesh.m_edges.Clear(); - m_isFlat = false; - } - - if (m_mesh.GetNTriangles() == 0) // we have to create the first polyhedron - { - ICHullError res = DoubleTriangle(); - if (res != ICHullErrorOK) { - return res; - } - else { - addedPoints += 3; - } - } - CircularList& vertices = m_mesh.GetVertices(); - while (!vertices.GetData().m_tag && addedPoints < nPointsCH) // not processed - { - if (!FindMaxVolumePoint((addedPoints > 4) ? minVolume : 0.0)) { - break; - } - vertices.GetData().m_tag = true; - if (ProcessPoint()) { - addedPoints++; - CleanUp(addedPoints); - if (!GetMesh().CheckConsistancy()) { - size_t nV = m_mesh.GetNVertices(); - CircularList& vertices = m_mesh.GetVertices(); - for (size_t v = 0; v < nV; ++v) { - if (vertices.GetData().m_name == sc_dummyIndex) { - vertices.Delete(); - break; - } - vertices.Next(); - } - return ICHullErrorInconsistent; - } - vertices.Next(); - } - } - // delete remaining points - while (!vertices.GetData().m_tag) { - vertices.Delete(); - } - if (m_isFlat) { - SArray*> trianglesToDuplicate; - size_t nT = m_mesh.GetNTriangles(); - for (size_t f = 0; f < nT; f++) { - TMMTriangle& currentTriangle = m_mesh.m_triangles.GetHead()->GetData(); - if (currentTriangle.m_vertices[0]->GetData().m_name == sc_dummyIndex || currentTriangle.m_vertices[1]->GetData().m_name == sc_dummyIndex || currentTriangle.m_vertices[2]->GetData().m_name == sc_dummyIndex) { - m_trianglesToDelete.PushBack(m_mesh.m_triangles.GetHead()); - for (int k = 0; k < 3; k++) { - for (int h = 0; h < 2; h++) { - if (currentTriangle.m_edges[k]->GetData().m_triangles[h] == m_mesh.m_triangles.GetHead()) { - currentTriangle.m_edges[k]->GetData().m_triangles[h] = 0; - break; - } - } - } - } - else { - trianglesToDuplicate.PushBack(m_mesh.m_triangles.GetHead()); - } - m_mesh.m_triangles.Next(); - } - size_t nE = m_mesh.GetNEdges(); - for (size_t e = 0; e < nE; e++) { - TMMEdge& currentEdge = m_mesh.m_edges.GetHead()->GetData(); - if (currentEdge.m_triangles[0] == 0 && currentEdge.m_triangles[1] == 0) { - m_edgesToDelete.PushBack(m_mesh.m_edges.GetHead()); - } - m_mesh.m_edges.Next(); - } - size_t nV = m_mesh.GetNVertices(); - CircularList& vertices = m_mesh.GetVertices(); - for (size_t v = 0; v < nV; ++v) { - if (vertices.GetData().m_name == sc_dummyIndex) { - vertices.Delete(); - } - else { - vertices.GetData().m_tag = false; - vertices.Next(); - } - } - CleanEdges(); - CleanTriangles(); - CircularListElement* newTriangle; - for (size_t t = 0; t < trianglesToDuplicate.Size(); t++) { - newTriangle = m_mesh.AddTriangle(); - newTriangle->GetData().m_vertices[0] = trianglesToDuplicate[t]->GetData().m_vertices[1]; - newTriangle->GetData().m_vertices[1] = trianglesToDuplicate[t]->GetData().m_vertices[0]; - newTriangle->GetData().m_vertices[2] = trianglesToDuplicate[t]->GetData().m_vertices[2]; - } - } - return ICHullErrorOK; -} -bool ICHull::FindMaxVolumePoint(const double minVolume) -{ - CircularList& vertices = m_mesh.GetVertices(); - CircularListElement* vMaxVolume = 0; - CircularListElement* vHeadPrev = vertices.GetHead()->GetPrev(); - - double maxVolume = minVolume; - double volume = 0.0; - while (!vertices.GetData().m_tag) // not processed - { - if (ComputePointVolume(volume, false)) { - if (maxVolume < volume) { - maxVolume = volume; - vMaxVolume = vertices.GetHead(); - } - vertices.Next(); - } - } - CircularListElement* vHead = vHeadPrev->GetNext(); - vertices.GetHead() = vHead; - if (!vMaxVolume) { - return false; - } - if (vMaxVolume != vHead) { - Vec3 pos = vHead->GetData().m_pos; - int id = vHead->GetData().m_name; - vHead->GetData().m_pos = vMaxVolume->GetData().m_pos; - vHead->GetData().m_name = vMaxVolume->GetData().m_name; - vMaxVolume->GetData().m_pos = pos; - vHead->GetData().m_name = id; - } - return true; -} -ICHullError ICHull::DoubleTriangle() -{ - // find three non colinear points - m_isFlat = false; - CircularList& vertices = m_mesh.GetVertices(); - CircularListElement* v0 = vertices.GetHead(); - while (Colinear(v0->GetData().m_pos, - v0->GetNext()->GetData().m_pos, - v0->GetNext()->GetNext()->GetData().m_pos)) { - if ((v0 = v0->GetNext()) == vertices.GetHead()) { - return ICHullErrorCoplanarPoints; - } - } - CircularListElement* v1 = v0->GetNext(); - CircularListElement* v2 = v1->GetNext(); - // mark points as processed - v0->GetData().m_tag = v1->GetData().m_tag = v2->GetData().m_tag = true; - - // create two triangles - CircularListElement* f0 = MakeFace(v0, v1, v2, 0); - MakeFace(v2, v1, v0, f0); - - // find a fourth non-coplanar point to form tetrahedron - CircularListElement* v3 = v2->GetNext(); - vertices.GetHead() = v3; - - double vol = ComputeVolume4(v0->GetData().m_pos, v1->GetData().m_pos, v2->GetData().m_pos, v3->GetData().m_pos); - while (fabs(vol) < sc_eps && !v3->GetNext()->GetData().m_tag) { - v3 = v3->GetNext(); - vol = ComputeVolume4(v0->GetData().m_pos, v1->GetData().m_pos, v2->GetData().m_pos, v3->GetData().m_pos); - } - if (fabs(vol) < sc_eps) { - // compute the barycenter - Vec3 bary(0.0, 0.0, 0.0); - CircularListElement* vBary = v0; - do { - bary += vBary->GetData().m_pos; - } while ((vBary = vBary->GetNext()) != v0); - bary /= static_cast(vertices.GetSize()); - - // Compute the normal to the plane - Vec3 p0 = v0->GetData().m_pos; - Vec3 p1 = v1->GetData().m_pos; - Vec3 p2 = v2->GetData().m_pos; - m_normal = (p1 - p0) ^ (p2 - p0); - m_normal.Normalize(); - // add dummy vertex placed at (bary + normal) - vertices.GetHead() = v2; - Vec3 newPt = bary + m_normal; - AddPoint(newPt, sc_dummyIndex); - m_isFlat = true; - return ICHullErrorOK; - } - else if (v3 != vertices.GetHead()) { - TMMVertex temp; - temp.m_name = v3->GetData().m_name; - temp.m_pos = v3->GetData().m_pos; - v3->GetData().m_name = vertices.GetHead()->GetData().m_name; - v3->GetData().m_pos = vertices.GetHead()->GetData().m_pos; - vertices.GetHead()->GetData().m_name = temp.m_name; - vertices.GetHead()->GetData().m_pos = temp.m_pos; - } - return ICHullErrorOK; -} -CircularListElement* ICHull::MakeFace(CircularListElement* v0, - CircularListElement* v1, - CircularListElement* v2, - CircularListElement* fold) -{ - CircularListElement* e0; - CircularListElement* e1; - CircularListElement* e2; - int index = 0; - if (!fold) // if first face to be created - { - e0 = m_mesh.AddEdge(); // create the three edges - e1 = m_mesh.AddEdge(); - e2 = m_mesh.AddEdge(); - } - else // otherwise re-use existing edges (in reverse order) - { - e0 = fold->GetData().m_edges[2]; - e1 = fold->GetData().m_edges[1]; - e2 = fold->GetData().m_edges[0]; - index = 1; - } - e0->GetData().m_vertices[0] = v0; - e0->GetData().m_vertices[1] = v1; - e1->GetData().m_vertices[0] = v1; - e1->GetData().m_vertices[1] = v2; - e2->GetData().m_vertices[0] = v2; - e2->GetData().m_vertices[1] = v0; - // create the new face - CircularListElement* f = m_mesh.AddTriangle(); - f->GetData().m_edges[0] = e0; - f->GetData().m_edges[1] = e1; - f->GetData().m_edges[2] = e2; - f->GetData().m_vertices[0] = v0; - f->GetData().m_vertices[1] = v1; - f->GetData().m_vertices[2] = v2; - // link edges to face f - e0->GetData().m_triangles[index] = e1->GetData().m_triangles[index] = e2->GetData().m_triangles[index] = f; - return f; -} -CircularListElement* ICHull::MakeConeFace(CircularListElement* e, CircularListElement* p) -{ - // create two new edges if they don't already exist - CircularListElement* newEdges[2]; - for (int i = 0; i < 2; ++i) { - if (!(newEdges[i] = e->GetData().m_vertices[i]->GetData().m_duplicate)) { // if the edge doesn't exits add it and mark the vertex as duplicated - newEdges[i] = m_mesh.AddEdge(); - newEdges[i]->GetData().m_vertices[0] = e->GetData().m_vertices[i]; - newEdges[i]->GetData().m_vertices[1] = p; - e->GetData().m_vertices[i]->GetData().m_duplicate = newEdges[i]; - } - } - // make the new face - CircularListElement* newFace = m_mesh.AddTriangle(); - newFace->GetData().m_edges[0] = e; - newFace->GetData().m_edges[1] = newEdges[0]; - newFace->GetData().m_edges[2] = newEdges[1]; - MakeCCW(newFace, e, p); - for (int i = 0; i < 2; ++i) { - for (int j = 0; j < 2; ++j) { - if (!newEdges[i]->GetData().m_triangles[j]) { - newEdges[i]->GetData().m_triangles[j] = newFace; - break; - } - } - } - return newFace; -} -bool ICHull::ComputePointVolume(double& totalVolume, bool markVisibleFaces) -{ - // mark visible faces - CircularListElement* fHead = m_mesh.GetTriangles().GetHead(); - CircularListElement* f = fHead; - CircularList& vertices = m_mesh.GetVertices(); - CircularListElement* vertex0 = vertices.GetHead(); - bool visible = false; - Vec3 pos0 = Vec3(vertex0->GetData().m_pos.X(), - vertex0->GetData().m_pos.Y(), - vertex0->GetData().m_pos.Z()); - double vol = 0.0; - totalVolume = 0.0; - Vec3 ver0, ver1, ver2; - do { - ver0.X() = f->GetData().m_vertices[0]->GetData().m_pos.X(); - ver0.Y() = f->GetData().m_vertices[0]->GetData().m_pos.Y(); - ver0.Z() = f->GetData().m_vertices[0]->GetData().m_pos.Z(); - ver1.X() = f->GetData().m_vertices[1]->GetData().m_pos.X(); - ver1.Y() = f->GetData().m_vertices[1]->GetData().m_pos.Y(); - ver1.Z() = f->GetData().m_vertices[1]->GetData().m_pos.Z(); - ver2.X() = f->GetData().m_vertices[2]->GetData().m_pos.X(); - ver2.Y() = f->GetData().m_vertices[2]->GetData().m_pos.Y(); - ver2.Z() = f->GetData().m_vertices[2]->GetData().m_pos.Z(); - vol = ComputeVolume4(ver0, ver1, ver2, pos0); - if (vol < -sc_eps) { - vol = fabs(vol); - totalVolume += vol; - if (markVisibleFaces) { - f->GetData().m_visible = true; - m_trianglesToDelete.PushBack(f); - } - visible = true; - } - f = f->GetNext(); - } while (f != fHead); - - if (m_trianglesToDelete.Size() == m_mesh.m_triangles.GetSize()) { - for (size_t i = 0; i < m_trianglesToDelete.Size(); i++) { - m_trianglesToDelete[i]->GetData().m_visible = false; - } - visible = false; - } - // if no faces visible from p then p is inside the hull - if (!visible && markVisibleFaces) { - vertices.Delete(); - m_trianglesToDelete.Resize(0); - return false; - } - return true; -} -bool ICHull::ProcessPoint() -{ - double totalVolume = 0.0; - if (!ComputePointVolume(totalVolume, true)) { - return false; - } - // Mark edges in interior of visible region for deletion. - // Create a new face based on each border edge - CircularListElement* v0 = m_mesh.GetVertices().GetHead(); - CircularListElement* eHead = m_mesh.GetEdges().GetHead(); - CircularListElement* e = eHead; - CircularListElement* tmp = 0; - int nvisible = 0; - m_edgesToDelete.Resize(0); - m_edgesToUpdate.Resize(0); - do { - tmp = e->GetNext(); - nvisible = 0; - for (int k = 0; k < 2; k++) { - if (e->GetData().m_triangles[k]->GetData().m_visible) { - nvisible++; - } - } - if (nvisible == 2) { - m_edgesToDelete.PushBack(e); - } - else if (nvisible == 1) { - e->GetData().m_newFace = MakeConeFace(e, v0); - m_edgesToUpdate.PushBack(e); - } - e = tmp; - } while (e != eHead); - return true; -} -bool ICHull::MakeCCW(CircularListElement* f, - CircularListElement* e, - CircularListElement* v) -{ - // the visible face adjacent to e - CircularListElement* fv; - if (e->GetData().m_triangles[0]->GetData().m_visible) { - fv = e->GetData().m_triangles[0]; - } - else { - fv = e->GetData().m_triangles[1]; - } - - // set vertex[0] and vertex[1] to have the same orientation as the corresponding vertices of fv. - int i; // index of e->m_vertices[0] in fv - CircularListElement* v0 = e->GetData().m_vertices[0]; - CircularListElement* v1 = e->GetData().m_vertices[1]; - for (i = 0; fv->GetData().m_vertices[i] != v0; i++) - ; - - if (fv->GetData().m_vertices[(i + 1) % 3] != e->GetData().m_vertices[1]) { - f->GetData().m_vertices[0] = v1; - f->GetData().m_vertices[1] = v0; - } - else { - f->GetData().m_vertices[0] = v0; - f->GetData().m_vertices[1] = v1; - // swap edges - CircularListElement* tmp = f->GetData().m_edges[0]; - f->GetData().m_edges[0] = f->GetData().m_edges[1]; - f->GetData().m_edges[1] = tmp; - } - f->GetData().m_vertices[2] = v; - return true; -} -bool ICHull::CleanUp(unsigned int& addedPoints) -{ - bool r0 = CleanEdges(); - bool r1 = CleanTriangles(); - bool r2 = CleanVertices(addedPoints); - return r0 && r1 && r2; -} -bool ICHull::CleanEdges() -{ - // integrate the new faces into the data structure - CircularListElement* e; - const size_t ne_update = m_edgesToUpdate.Size(); - for (size_t i = 0; i < ne_update; ++i) { - e = m_edgesToUpdate[i]; - if (e->GetData().m_newFace) { - if (e->GetData().m_triangles[0]->GetData().m_visible) { - e->GetData().m_triangles[0] = e->GetData().m_newFace; - } - else { - e->GetData().m_triangles[1] = e->GetData().m_newFace; - } - e->GetData().m_newFace = 0; - } - } - // delete edges maked for deletion - CircularList& edges = m_mesh.GetEdges(); - const size_t ne_delete = m_edgesToDelete.Size(); - for (size_t i = 0; i < ne_delete; ++i) { - edges.Delete(m_edgesToDelete[i]); - } - m_edgesToDelete.Resize(0); - m_edgesToUpdate.Resize(0); - return true; -} -bool ICHull::CleanTriangles() -{ - CircularList& triangles = m_mesh.GetTriangles(); - const size_t nt_delete = m_trianglesToDelete.Size(); - for (size_t i = 0; i < nt_delete; ++i) { - triangles.Delete(m_trianglesToDelete[i]); - } - m_trianglesToDelete.Resize(0); - return true; -} -bool ICHull::CleanVertices(unsigned int& addedPoints) -{ - // mark all vertices incident to some undeleted edge as on the hull - CircularList& edges = m_mesh.GetEdges(); - CircularListElement* e = edges.GetHead(); - size_t nE = edges.GetSize(); - for (size_t i = 0; i < nE; i++) { - e->GetData().m_vertices[0]->GetData().m_onHull = true; - e->GetData().m_vertices[1]->GetData().m_onHull = true; - e = e->GetNext(); - } - // delete all the vertices that have been processed but are not on the hull - CircularList& vertices = m_mesh.GetVertices(); - CircularListElement* vHead = vertices.GetHead(); - CircularListElement* v = vHead; - v = v->GetPrev(); - do { - if (v->GetData().m_tag && !v->GetData().m_onHull) { - CircularListElement* tmp = v->GetPrev(); - vertices.Delete(v); - v = tmp; - addedPoints--; - } - else { - v->GetData().m_duplicate = 0; - v->GetData().m_onHull = false; - v = v->GetPrev(); - } - } while (v->GetData().m_tag && v != vHead); - return true; -} -void ICHull::Clear() -{ - m_mesh.Clear(); - m_edgesToDelete.Resize(0); - m_edgesToUpdate.Resize(0); - m_trianglesToDelete.Resize(0); - m_isFlat = false; -} -const ICHull& ICHull::operator=(ICHull& rhs) -{ - if (&rhs != this) { - m_mesh.Copy(rhs.m_mesh); - m_edgesToDelete = rhs.m_edgesToDelete; - m_edgesToUpdate = rhs.m_edgesToUpdate; - m_trianglesToDelete = rhs.m_trianglesToDelete; - m_isFlat = rhs.m_isFlat; - } - return (*this); -} -bool ICHull::IsInside(const Vec3& pt0, const double eps) -{ - const Vec3 pt(pt0.X(), pt0.Y(), pt0.Z()); - if (m_isFlat) { - size_t nT = m_mesh.m_triangles.GetSize(); - Vec3 ver0, ver1, ver2, a, b, c; - double u, v; - for (size_t t = 0; t < nT; t++) { - ver0.X() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[0]->GetData().m_pos.X(); - ver0.Y() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[0]->GetData().m_pos.Y(); - ver0.Z() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[0]->GetData().m_pos.Z(); - ver1.X() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[1]->GetData().m_pos.X(); - ver1.Y() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[1]->GetData().m_pos.Y(); - ver1.Z() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[1]->GetData().m_pos.Z(); - ver2.X() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[2]->GetData().m_pos.X(); - ver2.Y() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[2]->GetData().m_pos.Y(); - ver2.Z() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[2]->GetData().m_pos.Z(); - a = ver1 - ver0; - b = ver2 - ver0; - c = pt - ver0; - u = c * a; - v = c * b; - if (u >= 0.0 && u <= 1.0 && v >= 0.0 && u + v <= 1.0) { - return true; - } - m_mesh.m_triangles.Next(); - } - return false; - } - else { - size_t nT = m_mesh.m_triangles.GetSize(); - Vec3 ver0, ver1, ver2; - double vol; - for (size_t t = 0; t < nT; t++) { - ver0.X() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[0]->GetData().m_pos.X(); - ver0.Y() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[0]->GetData().m_pos.Y(); - ver0.Z() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[0]->GetData().m_pos.Z(); - ver1.X() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[1]->GetData().m_pos.X(); - ver1.Y() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[1]->GetData().m_pos.Y(); - ver1.Z() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[1]->GetData().m_pos.Z(); - ver2.X() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[2]->GetData().m_pos.X(); - ver2.Y() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[2]->GetData().m_pos.Y(); - ver2.Z() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[2]->GetData().m_pos.Z(); - vol = ComputeVolume4(ver0, ver1, ver2, pt); - if (vol < eps) { - return false; - } - m_mesh.m_triangles.Next(); - } - return true; - } -} -} diff --git a/extern/bullet/src/Extras/VHACD/src/vhacdManifoldMesh.cpp b/extern/bullet/src/Extras/VHACD/src/vhacdManifoldMesh.cpp deleted file mode 100644 index 6f5db06f1cf4..000000000000 --- a/extern/bullet/src/Extras/VHACD/src/vhacdManifoldMesh.cpp +++ /dev/null @@ -1,202 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) - All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#include "Extras/VHACD/inc/vhacdManifoldMesh.h" -namespace VHACD { -TMMVertex::TMMVertex(void) -{ - Initialize(); -} -void TMMVertex::Initialize() -{ - m_name = 0; - m_id = 0; - m_duplicate = 0; - m_onHull = false; - m_tag = false; -} - -TMMVertex::~TMMVertex(void) -{ -} -TMMEdge::TMMEdge(void) -{ - Initialize(); -} -void TMMEdge::Initialize() -{ - m_id = 0; - m_triangles[0] = m_triangles[1] = m_newFace = 0; - m_vertices[0] = m_vertices[1] = 0; -} -TMMEdge::~TMMEdge(void) -{ -} -void TMMTriangle::Initialize() -{ - m_id = 0; - for (int i = 0; i < 3; i++) { - m_edges[i] = 0; - m_vertices[0] = 0; - } - m_visible = false; -} -TMMTriangle::TMMTriangle(void) -{ - Initialize(); -} -TMMTriangle::~TMMTriangle(void) -{ -} -TMMesh::TMMesh() -{ -} -TMMesh::~TMMesh(void) -{ -} -void TMMesh::GetIFS(Vec3* const points, Vec3* const triangles) -{ - size_t nV = m_vertices.GetSize(); - size_t nT = m_triangles.GetSize(); - - for (size_t v = 0; v < nV; v++) { - points[v] = m_vertices.GetData().m_pos; - m_vertices.GetData().m_id = v; - m_vertices.Next(); - } - for (size_t f = 0; f < nT; f++) { - TMMTriangle& currentTriangle = m_triangles.GetData(); - triangles[f].X() = static_cast(currentTriangle.m_vertices[0]->GetData().m_id); - triangles[f].Y() = static_cast(currentTriangle.m_vertices[1]->GetData().m_id); - triangles[f].Z() = static_cast(currentTriangle.m_vertices[2]->GetData().m_id); - m_triangles.Next(); - } -} -void TMMesh::Clear() -{ - m_vertices.Clear(); - m_edges.Clear(); - m_triangles.Clear(); -} -void TMMesh::Copy(TMMesh& mesh) -{ - Clear(); - // updating the id's - size_t nV = mesh.m_vertices.GetSize(); - size_t nE = mesh.m_edges.GetSize(); - size_t nT = mesh.m_triangles.GetSize(); - for (size_t v = 0; v < nV; v++) { - mesh.m_vertices.GetData().m_id = v; - mesh.m_vertices.Next(); - } - for (size_t e = 0; e < nE; e++) { - mesh.m_edges.GetData().m_id = e; - mesh.m_edges.Next(); - } - for (size_t f = 0; f < nT; f++) { - mesh.m_triangles.GetData().m_id = f; - mesh.m_triangles.Next(); - } - // copying data - m_vertices = mesh.m_vertices; - m_edges = mesh.m_edges; - m_triangles = mesh.m_triangles; - - // generate mapping - CircularListElement** vertexMap = new CircularListElement*[nV]; - CircularListElement** edgeMap = new CircularListElement*[nE]; - CircularListElement** triangleMap = new CircularListElement*[nT]; - for (size_t v = 0; v < nV; v++) { - vertexMap[v] = m_vertices.GetHead(); - m_vertices.Next(); - } - for (size_t e = 0; e < nE; e++) { - edgeMap[e] = m_edges.GetHead(); - m_edges.Next(); - } - for (size_t f = 0; f < nT; f++) { - triangleMap[f] = m_triangles.GetHead(); - m_triangles.Next(); - } - - // updating pointers - for (size_t v = 0; v < nV; v++) { - if (vertexMap[v]->GetData().m_duplicate) { - vertexMap[v]->GetData().m_duplicate = edgeMap[vertexMap[v]->GetData().m_duplicate->GetData().m_id]; - } - } - for (size_t e = 0; e < nE; e++) { - if (edgeMap[e]->GetData().m_newFace) { - edgeMap[e]->GetData().m_newFace = triangleMap[edgeMap[e]->GetData().m_newFace->GetData().m_id]; - } - if (nT > 0) { - for (int f = 0; f < 2; f++) { - if (edgeMap[e]->GetData().m_triangles[f]) { - edgeMap[e]->GetData().m_triangles[f] = triangleMap[edgeMap[e]->GetData().m_triangles[f]->GetData().m_id]; - } - } - } - for (int v = 0; v < 2; v++) { - if (edgeMap[e]->GetData().m_vertices[v]) { - edgeMap[e]->GetData().m_vertices[v] = vertexMap[edgeMap[e]->GetData().m_vertices[v]->GetData().m_id]; - } - } - } - for (size_t f = 0; f < nT; f++) { - if (nE > 0) { - for (int e = 0; e < 3; e++) { - if (triangleMap[f]->GetData().m_edges[e]) { - triangleMap[f]->GetData().m_edges[e] = edgeMap[triangleMap[f]->GetData().m_edges[e]->GetData().m_id]; - } - } - } - for (int v = 0; v < 3; v++) { - if (triangleMap[f]->GetData().m_vertices[v]) { - triangleMap[f]->GetData().m_vertices[v] = vertexMap[triangleMap[f]->GetData().m_vertices[v]->GetData().m_id]; - } - } - } - delete[] vertexMap; - delete[] edgeMap; - delete[] triangleMap; -} -bool TMMesh::CheckConsistancy() -{ - size_t nE = m_edges.GetSize(); - size_t nT = m_triangles.GetSize(); - for (size_t e = 0; e < nE; e++) { - for (int f = 0; f < 2; f++) { - if (!m_edges.GetHead()->GetData().m_triangles[f]) { - return false; - } - } - m_edges.Next(); - } - for (size_t f = 0; f < nT; f++) { - for (int e = 0; e < 3; e++) { - int found = 0; - for (int k = 0; k < 2; k++) { - if (m_triangles.GetHead()->GetData().m_edges[e]->GetData().m_triangles[k] == m_triangles.GetHead()) { - found++; - } - } - if (found != 1) { - return false; - } - } - m_triangles.Next(); - } - return true; -} -} diff --git a/extern/bullet/src/Extras/VHACD/src/vhacdMesh.cpp b/extern/bullet/src/Extras/VHACD/src/vhacdMesh.cpp deleted file mode 100644 index 49f34a317a9e..000000000000 --- a/extern/bullet/src/Extras/VHACD/src/vhacdMesh.cpp +++ /dev/null @@ -1,323 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) - All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#define _CRT_SECURE_NO_WARNINGS - -#include "Extras/VHACD/inc/btConvexHullComputer.h" -#include "Extras/VHACD/inc/vhacdMesh.h" -#include -#include -#include -#include -#include -#include - -namespace VHACD { -Mesh::Mesh() -{ - m_diag = 1.0; -} -Mesh::~Mesh() -{ -} -double Mesh::ComputeVolume() const -{ - const size_t nV = GetNPoints(); - const size_t nT = GetNTriangles(); - if (nV == 0 || nT == 0) { - return 0.0; - } - - Vec3 bary(0.0, 0.0, 0.0); - for (size_t v = 0; v < nV; v++) { - bary += GetPoint(v); - } - bary /= static_cast(nV); - - Vec3 ver0, ver1, ver2; - double totalVolume = 0.0; - for (int t = 0; t < nT; t++) { - const Vec3& tri = GetTriangle(t); - ver0 = GetPoint(tri[0]); - ver1 = GetPoint(tri[1]); - ver2 = GetPoint(tri[2]); - totalVolume += ComputeVolume4(ver0, ver1, ver2, bary); - } - return totalVolume / 6.0; -} - -void Mesh::ComputeConvexHull(const double* const pts, - const size_t nPts) -{ - ResizePoints(0); - ResizeTriangles(0); - btConvexHullComputer ch; - ch.compute(pts, 3 * sizeof(double), (int)nPts, -1.0, -1.0); - for (int v = 0; v < ch.vertices.size(); v++) { - AddPoint(Vec3(ch.vertices[v].getX(), ch.vertices[v].getY(), ch.vertices[v].getZ())); - } - const int nt = ch.faces.size(); - for (int t = 0; t < nt; ++t) { - const btConvexHullComputer::Edge* sourceEdge = &(ch.edges[ch.faces[t]]); - int a = sourceEdge->getSourceVertex(); - int b = sourceEdge->getTargetVertex(); - const btConvexHullComputer::Edge* edge = sourceEdge->getNextEdgeOfFace(); - int c = edge->getTargetVertex(); - while (c != a) { - AddTriangle(Vec3(a, b, c)); - edge = edge->getNextEdgeOfFace(); - b = c; - c = edge->getTargetVertex(); - } - } -} -void Mesh::Clip(const Plane& plane, - SArray >& positivePart, - SArray >& negativePart) const -{ - const size_t nV = GetNPoints(); - if (nV == 0) { - return; - } - double d; - for (size_t v = 0; v < nV; v++) { - const Vec3& pt = GetPoint(v); - d = plane.m_a * pt[0] + plane.m_b * pt[1] + plane.m_c * pt[2] + plane.m_d; - if (d > 0.0) { - positivePart.PushBack(pt); - } - else if (d < 0.0) { - negativePart.PushBack(pt); - } - else { - positivePart.PushBack(pt); - negativePart.PushBack(pt); - } - } -} -bool Mesh::IsInside(const Vec3& pt) const -{ - const size_t nV = GetNPoints(); - const size_t nT = GetNTriangles(); - if (nV == 0 || nT == 0) { - return false; - } - Vec3 ver0, ver1, ver2; - double volume; - for (int t = 0; t < nT; t++) { - const Vec3& tri = GetTriangle(t); - ver0 = GetPoint(tri[0]); - ver1 = GetPoint(tri[1]); - ver2 = GetPoint(tri[2]); - volume = ComputeVolume4(ver0, ver1, ver2, pt); - if (volume < 0.0) { - return false; - } - } - return true; -} -double Mesh::ComputeDiagBB() -{ - const size_t nPoints = GetNPoints(); - if (nPoints == 0) - return 0.0; - Vec3 minBB = m_points[0]; - Vec3 maxBB = m_points[0]; - double x, y, z; - for (size_t v = 1; v < nPoints; v++) { - x = m_points[v][0]; - y = m_points[v][1]; - z = m_points[v][2]; - if (x < minBB[0]) - minBB[0] = x; - else if (x > maxBB[0]) - maxBB[0] = x; - if (y < minBB[1]) - minBB[1] = y; - else if (y > maxBB[1]) - maxBB[1] = y; - if (z < minBB[2]) - minBB[2] = z; - else if (z > maxBB[2]) - maxBB[2] = z; - } - return (m_diag = (maxBB - minBB).GetNorm()); -} - -#ifdef VHACD_DEBUG_MESH -bool Mesh::SaveVRML2(const std::string& fileName) const -{ - std::ofstream fout(fileName.c_str()); - if (fout.is_open()) { - const Material material; - - if (SaveVRML2(fout, material)) { - fout.close(); - return true; - } - return false; - } - return false; -} -bool Mesh::SaveVRML2(std::ofstream& fout, const Material& material) const -{ - if (fout.is_open()) { - fout.setf(std::ios::fixed, std::ios::floatfield); - fout.setf(std::ios::showpoint); - fout.precision(6); - size_t nV = m_points.Size(); - size_t nT = m_triangles.Size(); - fout << "#VRML V2.0 utf8" << std::endl; - fout << "" << std::endl; - fout << "# Vertices: " << nV << std::endl; - fout << "# Triangles: " << nT << std::endl; - fout << "" << std::endl; - fout << "Group {" << std::endl; - fout << " children [" << std::endl; - fout << " Shape {" << std::endl; - fout << " appearance Appearance {" << std::endl; - fout << " material Material {" << std::endl; - fout << " diffuseColor " << material.m_diffuseColor[0] << " " - << material.m_diffuseColor[1] << " " - << material.m_diffuseColor[2] << std::endl; - fout << " ambientIntensity " << material.m_ambientIntensity << std::endl; - fout << " specularColor " << material.m_specularColor[0] << " " - << material.m_specularColor[1] << " " - << material.m_specularColor[2] << std::endl; - fout << " emissiveColor " << material.m_emissiveColor[0] << " " - << material.m_emissiveColor[1] << " " - << material.m_emissiveColor[2] << std::endl; - fout << " shininess " << material.m_shininess << std::endl; - fout << " transparency " << material.m_transparency << std::endl; - fout << " }" << std::endl; - fout << " }" << std::endl; - fout << " geometry IndexedFaceSet {" << std::endl; - fout << " ccw TRUE" << std::endl; - fout << " solid TRUE" << std::endl; - fout << " convex TRUE" << std::endl; - if (nV > 0) { - fout << " coord DEF co Coordinate {" << std::endl; - fout << " point [" << std::endl; - for (size_t v = 0; v < nV; v++) { - fout << " " << m_points[v][0] << " " - << m_points[v][1] << " " - << m_points[v][2] << "," << std::endl; - } - fout << " ]" << std::endl; - fout << " }" << std::endl; - } - if (nT > 0) { - fout << " coordIndex [ " << std::endl; - for (size_t f = 0; f < nT; f++) { - fout << " " << m_triangles[f][0] << ", " - << m_triangles[f][1] << ", " - << m_triangles[f][2] << ", -1," << std::endl; - } - fout << " ]" << std::endl; - } - fout << " }" << std::endl; - fout << " }" << std::endl; - fout << " ]" << std::endl; - fout << "}" << std::endl; - return true; - } - return false; -} -bool Mesh::SaveOFF(const std::string& fileName) const -{ - std::ofstream fout(fileName.c_str()); - if (fout.is_open()) { - size_t nV = m_points.Size(); - size_t nT = m_triangles.Size(); - fout << "OFF" << std::endl; - fout << nV << " " << nT << " " << 0 << std::endl; - for (size_t v = 0; v < nV; v++) { - fout << m_points[v][0] << " " - << m_points[v][1] << " " - << m_points[v][2] << std::endl; - } - for (size_t f = 0; f < nT; f++) { - fout << "3 " << m_triangles[f][0] << " " - << m_triangles[f][1] << " " - << m_triangles[f][2] << std::endl; - } - fout.close(); - return true; - } - return false; -} - -bool Mesh::LoadOFF(const std::string& fileName, bool invert) -{ - FILE* fid = fopen(fileName.c_str(), "r"); - if (fid) { - const std::string strOFF("OFF"); - char temp[1024]; - fscanf(fid, "%s", temp); - if (std::string(temp) != strOFF) { - fclose(fid); - return false; - } - else { - int nv = 0; - int nf = 0; - int ne = 0; - fscanf(fid, "%i", &nv); - fscanf(fid, "%i", &nf); - fscanf(fid, "%i", &ne); - m_points.Resize(nv); - m_triangles.Resize(nf); - Vec3 coord; - float x, y, z; - for (int p = 0; p < nv; p++) { - fscanf(fid, "%f", &x); - fscanf(fid, "%f", &y); - fscanf(fid, "%f", &z); - m_points[p][0] = x; - m_points[p][1] = y; - m_points[p][2] = z; - } - int i, j, k, s; - for (int t = 0; t < nf; ++t) { - fscanf(fid, "%i", &s); - if (s == 3) { - fscanf(fid, "%i", &i); - fscanf(fid, "%i", &j); - fscanf(fid, "%i", &k); - m_triangles[t][0] = i; - if (invert) { - m_triangles[t][1] = k; - m_triangles[t][2] = j; - } - else { - m_triangles[t][1] = j; - m_triangles[t][2] = k; - } - } - else // Fix me: support only triangular meshes - { - for (int h = 0; h < s; ++h) - fscanf(fid, "%i", &s); - } - } - fclose(fid); - } - } - else { - return false; - } - return true; -} -#endif // VHACD_DEBUG_MESH -} diff --git a/extern/bullet/src/Extras/VHACD/src/vhacdVolume.cpp b/extern/bullet/src/Extras/VHACD/src/vhacdVolume.cpp deleted file mode 100644 index 8677f3233752..000000000000 --- a/extern/bullet/src/Extras/VHACD/src/vhacdVolume.cpp +++ /dev/null @@ -1,1617 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) - All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#define _CRT_SECURE_NO_WARNINGS -#include "Extras/VHACD/inc/btConvexHullComputer.h" -#include "Extras/VHACD/inc/vhacdVolume.h" -#include -#include -#include -#include -#include - -namespace VHACD { -/********************************************************/ -/* AABB-triangle overlap test code */ -/* by Tomas Akenine-Möller */ -/* Function: int triBoxOverlap(float boxcenter[3], */ -/* float boxhalfsize[3],float triverts[3][3]); */ -/* History: */ -/* 2001-03-05: released the code in its first version */ -/* 2001-06-18: changed the order of the tests, faster */ -/* */ -/* Acknowledgement: Many thanks to Pierre Terdiman for */ -/* suggestions and discussions on how to optimize code. */ -/* Thanks to David Hunt for finding a ">="-bug! */ -/********************************************************/ - -#define X 0 -#define Y 1 -#define Z 2 -#define FINDMINMAX(x0, x1, x2, min, max) \ - min = max = x0; \ - if (x1 < min) \ - min = x1; \ - if (x1 > max) \ - max = x1; \ - if (x2 < min) \ - min = x2; \ - if (x2 > max) \ - max = x2; - -#define AXISTEST_X01(a, b, fa, fb) \ - p0 = a * v0[Y] - b * v0[Z]; \ - p2 = a * v2[Y] - b * v2[Z]; \ - if (p0 < p2) { \ - min = p0; \ - max = p2; \ - } \ - else { \ - min = p2; \ - max = p0; \ - } \ - rad = fa * boxhalfsize[Y] + fb * boxhalfsize[Z]; \ - if (min > rad || max < -rad) \ - return 0; - -#define AXISTEST_X2(a, b, fa, fb) \ - p0 = a * v0[Y] - b * v0[Z]; \ - p1 = a * v1[Y] - b * v1[Z]; \ - if (p0 < p1) { \ - min = p0; \ - max = p1; \ - } \ - else { \ - min = p1; \ - max = p0; \ - } \ - rad = fa * boxhalfsize[Y] + fb * boxhalfsize[Z]; \ - if (min > rad || max < -rad) \ - return 0; - -#define AXISTEST_Y02(a, b, fa, fb) \ - p0 = -a * v0[X] + b * v0[Z]; \ - p2 = -a * v2[X] + b * v2[Z]; \ - if (p0 < p2) { \ - min = p0; \ - max = p2; \ - } \ - else { \ - min = p2; \ - max = p0; \ - } \ - rad = fa * boxhalfsize[X] + fb * boxhalfsize[Z]; \ - if (min > rad || max < -rad) \ - return 0; - -#define AXISTEST_Y1(a, b, fa, fb) \ - p0 = -a * v0[X] + b * v0[Z]; \ - p1 = -a * v1[X] + b * v1[Z]; \ - if (p0 < p1) { \ - min = p0; \ - max = p1; \ - } \ - else { \ - min = p1; \ - max = p0; \ - } \ - rad = fa * boxhalfsize[X] + fb * boxhalfsize[Z]; \ - if (min > rad || max < -rad) \ - return 0; - -#define AXISTEST_Z12(a, b, fa, fb) \ - p1 = a * v1[X] - b * v1[Y]; \ - p2 = a * v2[X] - b * v2[Y]; \ - if (p2 < p1) { \ - min = p2; \ - max = p1; \ - } \ - else { \ - min = p1; \ - max = p2; \ - } \ - rad = fa * boxhalfsize[X] + fb * boxhalfsize[Y]; \ - if (min > rad || max < -rad) \ - return 0; - -#define AXISTEST_Z0(a, b, fa, fb) \ - p0 = a * v0[X] - b * v0[Y]; \ - p1 = a * v1[X] - b * v1[Y]; \ - if (p0 < p1) { \ - min = p0; \ - max = p1; \ - } \ - else { \ - min = p1; \ - max = p0; \ - } \ - rad = fa * boxhalfsize[X] + fb * boxhalfsize[Y]; \ - if (min > rad || max < -rad) \ - return 0; - -int PlaneBoxOverlap(const Vec3& normal, - const Vec3& vert, - const Vec3& maxbox) -{ - int q; - Vec3 vmin, vmax; - double v; - for (q = X; q <= Z; q++) { - v = vert[q]; - if (normal[q] > 0.0) { - vmin[q] = -maxbox[q] - v; - vmax[q] = maxbox[q] - v; - } - else { - vmin[q] = maxbox[q] - v; - vmax[q] = -maxbox[q] - v; - } - } - if (normal * vmin > 0.0) - return 0; - if (normal * vmax >= 0.0) - return 1; - return 0; -} - -int TriBoxOverlap(const Vec3& boxcenter, - const Vec3& boxhalfsize, - const Vec3& triver0, - const Vec3& triver1, - const Vec3& triver2) -{ - /* use separating axis theorem to test overlap between triangle and box */ - /* need to test for overlap in these directions: */ - /* 1) the {x,y,z}-directions (actually, since we use the AABB of the triangle */ - /* we do not even need to test these) */ - /* 2) normal of the triangle */ - /* 3) crossproduct(edge from tri, {x,y,z}-directin) */ - /* this gives 3x3=9 more tests */ - - Vec3 v0, v1, v2; - double min, max, p0, p1, p2, rad, fex, fey, fez; // -NJMP- "d" local variable removed - Vec3 normal, e0, e1, e2; - - /* This is the fastest branch on Sun */ - /* move everything so that the boxcenter is in (0,0,0) */ - - v0 = triver0 - boxcenter; - v1 = triver1 - boxcenter; - v2 = triver2 - boxcenter; - - /* compute triangle edges */ - e0 = v1 - v0; /* tri edge 0 */ - e1 = v2 - v1; /* tri edge 1 */ - e2 = v0 - v2; /* tri edge 2 */ - - /* Bullet 3: */ - /* test the 9 tests first (this was faster) */ - fex = fabs(e0[X]); - fey = fabs(e0[Y]); - fez = fabs(e0[Z]); - - AXISTEST_X01(e0[Z], e0[Y], fez, fey); - AXISTEST_Y02(e0[Z], e0[X], fez, fex); - AXISTEST_Z12(e0[Y], e0[X], fey, fex); - - fex = fabs(e1[X]); - fey = fabs(e1[Y]); - fez = fabs(e1[Z]); - - AXISTEST_X01(e1[Z], e1[Y], fez, fey); - AXISTEST_Y02(e1[Z], e1[X], fez, fex); - AXISTEST_Z0(e1[Y], e1[X], fey, fex); - - fex = fabs(e2[X]); - fey = fabs(e2[Y]); - fez = fabs(e2[Z]); - - AXISTEST_X2(e2[Z], e2[Y], fez, fey); - AXISTEST_Y1(e2[Z], e2[X], fez, fex); - AXISTEST_Z12(e2[Y], e2[X], fey, fex); - - /* Bullet 1: */ - /* first test overlap in the {x,y,z}-directions */ - /* find min, max of the triangle each direction, and test for overlap in */ - /* that direction -- this is equivalent to testing a minimal AABB around */ - /* the triangle against the AABB */ - - /* test in X-direction */ - FINDMINMAX(v0[X], v1[X], v2[X], min, max); - if (min > boxhalfsize[X] || max < -boxhalfsize[X]) - return 0; - - /* test in Y-direction */ - FINDMINMAX(v0[Y], v1[Y], v2[Y], min, max); - if (min > boxhalfsize[Y] || max < -boxhalfsize[Y]) - return 0; - - /* test in Z-direction */ - FINDMINMAX(v0[Z], v1[Z], v2[Z], min, max); - if (min > boxhalfsize[Z] || max < -boxhalfsize[Z]) - return 0; - - /* Bullet 2: */ - /* test if the box intersects the plane of the triangle */ - /* compute plane equation of triangle: normal*x+d=0 */ - normal = e0 ^ e1; - - if (!PlaneBoxOverlap(normal, v0, boxhalfsize)) - return 0; - return 1; /* box and triangle overlaps */ -} - -// Slightly modified version of Stan Melax's code for 3x3 matrix diagonalization (Thanks Stan!) -// source: http://www.melax.com/diag.html?attredirects=0 -void Diagonalize(const double (&A)[3][3], double (&Q)[3][3], double (&D)[3][3]) -{ - // A must be a symmetric matrix. - // returns Q and D such that - // Diagonal matrix D = QT * A * Q; and A = Q*D*QT - const int maxsteps = 24; // certainly wont need that many. - int k0, k1, k2; - double o[3], m[3]; - double q[4] = { 0.0, 0.0, 0.0, 1.0 }; - double jr[4]; - double sqw, sqx, sqy, sqz; - double tmp1, tmp2, mq; - double AQ[3][3]; - double thet, sgn, t, c; - for (int i = 0; i < maxsteps; ++i) { - // quat to matrix - sqx = q[0] * q[0]; - sqy = q[1] * q[1]; - sqz = q[2] * q[2]; - sqw = q[3] * q[3]; - Q[0][0] = (sqx - sqy - sqz + sqw); - Q[1][1] = (-sqx + sqy - sqz + sqw); - Q[2][2] = (-sqx - sqy + sqz + sqw); - tmp1 = q[0] * q[1]; - tmp2 = q[2] * q[3]; - Q[1][0] = 2.0 * (tmp1 + tmp2); - Q[0][1] = 2.0 * (tmp1 - tmp2); - tmp1 = q[0] * q[2]; - tmp2 = q[1] * q[3]; - Q[2][0] = 2.0 * (tmp1 - tmp2); - Q[0][2] = 2.0 * (tmp1 + tmp2); - tmp1 = q[1] * q[2]; - tmp2 = q[0] * q[3]; - Q[2][1] = 2.0 * (tmp1 + tmp2); - Q[1][2] = 2.0 * (tmp1 - tmp2); - - // AQ = A * Q - AQ[0][0] = Q[0][0] * A[0][0] + Q[1][0] * A[0][1] + Q[2][0] * A[0][2]; - AQ[0][1] = Q[0][1] * A[0][0] + Q[1][1] * A[0][1] + Q[2][1] * A[0][2]; - AQ[0][2] = Q[0][2] * A[0][0] + Q[1][2] * A[0][1] + Q[2][2] * A[0][2]; - AQ[1][0] = Q[0][0] * A[0][1] + Q[1][0] * A[1][1] + Q[2][0] * A[1][2]; - AQ[1][1] = Q[0][1] * A[0][1] + Q[1][1] * A[1][1] + Q[2][1] * A[1][2]; - AQ[1][2] = Q[0][2] * A[0][1] + Q[1][2] * A[1][1] + Q[2][2] * A[1][2]; - AQ[2][0] = Q[0][0] * A[0][2] + Q[1][0] * A[1][2] + Q[2][0] * A[2][2]; - AQ[2][1] = Q[0][1] * A[0][2] + Q[1][1] * A[1][2] + Q[2][1] * A[2][2]; - AQ[2][2] = Q[0][2] * A[0][2] + Q[1][2] * A[1][2] + Q[2][2] * A[2][2]; - // D = Qt * AQ - D[0][0] = AQ[0][0] * Q[0][0] + AQ[1][0] * Q[1][0] + AQ[2][0] * Q[2][0]; - D[0][1] = AQ[0][0] * Q[0][1] + AQ[1][0] * Q[1][1] + AQ[2][0] * Q[2][1]; - D[0][2] = AQ[0][0] * Q[0][2] + AQ[1][0] * Q[1][2] + AQ[2][0] * Q[2][2]; - D[1][0] = AQ[0][1] * Q[0][0] + AQ[1][1] * Q[1][0] + AQ[2][1] * Q[2][0]; - D[1][1] = AQ[0][1] * Q[0][1] + AQ[1][1] * Q[1][1] + AQ[2][1] * Q[2][1]; - D[1][2] = AQ[0][1] * Q[0][2] + AQ[1][1] * Q[1][2] + AQ[2][1] * Q[2][2]; - D[2][0] = AQ[0][2] * Q[0][0] + AQ[1][2] * Q[1][0] + AQ[2][2] * Q[2][0]; - D[2][1] = AQ[0][2] * Q[0][1] + AQ[1][2] * Q[1][1] + AQ[2][2] * Q[2][1]; - D[2][2] = AQ[0][2] * Q[0][2] + AQ[1][2] * Q[1][2] + AQ[2][2] * Q[2][2]; - o[0] = D[1][2]; - o[1] = D[0][2]; - o[2] = D[0][1]; - m[0] = fabs(o[0]); - m[1] = fabs(o[1]); - m[2] = fabs(o[2]); - - k0 = (m[0] > m[1] && m[0] > m[2]) ? 0 : (m[1] > m[2]) ? 1 : 2; // index of largest element of offdiag - k1 = (k0 + 1) % 3; - k2 = (k0 + 2) % 3; - if (o[k0] == 0.0) { - break; // diagonal already - } - thet = (D[k2][k2] - D[k1][k1]) / (2.0 * o[k0]); - sgn = (thet > 0.0) ? 1.0 : -1.0; - thet *= sgn; // make it positive - t = sgn / (thet + ((thet < 1.E6) ? sqrt(thet * thet + 1.0) : thet)); // sign(T)/(|T|+sqrt(T^2+1)) - c = 1.0 / sqrt(t * t + 1.0); // c= 1/(t^2+1) , t=s/c - if (c == 1.0) { - break; // no room for improvement - reached machine precision. - } - jr[0] = jr[1] = jr[2] = jr[3] = 0.0; - jr[k0] = sgn * sqrt((1.0 - c) / 2.0); // using 1/2 angle identity sin(a/2) = sqrt((1-cos(a))/2) - jr[k0] *= -1.0; // since our quat-to-matrix convention was for v*M instead of M*v - jr[3] = sqrt(1.0 - jr[k0] * jr[k0]); - if (jr[3] == 1.0) { - break; // reached limits of floating point precision - } - q[0] = (q[3] * jr[0] + q[0] * jr[3] + q[1] * jr[2] - q[2] * jr[1]); - q[1] = (q[3] * jr[1] - q[0] * jr[2] + q[1] * jr[3] + q[2] * jr[0]); - q[2] = (q[3] * jr[2] + q[0] * jr[1] - q[1] * jr[0] + q[2] * jr[3]); - q[3] = (q[3] * jr[3] - q[0] * jr[0] - q[1] * jr[1] - q[2] * jr[2]); - mq = sqrt(q[0] * q[0] + q[1] * q[1] + q[2] * q[2] + q[3] * q[3]); - q[0] /= mq; - q[1] /= mq; - q[2] /= mq; - q[3] /= mq; - } -} -const double TetrahedronSet::EPS = 0.0000000000001; -VoxelSet::VoxelSet() -{ - m_minBB[0] = m_minBB[1] = m_minBB[2] = 0.0; - m_minBBVoxels[0] = m_minBBVoxels[1] = m_minBBVoxels[2] = 0; - m_maxBBVoxels[0] = m_maxBBVoxels[1] = m_maxBBVoxels[2] = 1; - m_minBBPts[0] = m_minBBPts[1] = m_minBBPts[2] = 0; - m_maxBBPts[0] = m_maxBBPts[1] = m_maxBBPts[2] = 1; - m_barycenter[0] = m_barycenter[1] = m_barycenter[2] = 0; - m_barycenterPCA[0] = m_barycenterPCA[1] = m_barycenterPCA[2] = 0.0; - m_scale = 1.0; - m_unitVolume = 1.0; - m_numVoxelsOnSurface = 0; - m_numVoxelsInsideSurface = 0; - memset(m_Q, 0, sizeof(double) * 9); - memset(m_D, 0, sizeof(double) * 9); -} -VoxelSet::~VoxelSet(void) -{ -} -void VoxelSet::ComputeBB() -{ - const size_t nVoxels = m_voxels.Size(); - if (nVoxels == 0) - return; - for (int h = 0; h < 3; ++h) { - m_minBBVoxels[h] = m_voxels[0].m_coord[h]; - m_maxBBVoxels[h] = m_voxels[0].m_coord[h]; - } - Vec3 bary(0.0); - for (size_t p = 0; p < nVoxels; ++p) { - for (int h = 0; h < 3; ++h) { - bary[h] += m_voxels[p].m_coord[h]; - if (m_minBBVoxels[h] > m_voxels[p].m_coord[h]) - m_minBBVoxels[h] = m_voxels[p].m_coord[h]; - if (m_maxBBVoxels[h] < m_voxels[p].m_coord[h]) - m_maxBBVoxels[h] = m_voxels[p].m_coord[h]; - } - } - bary /= (double)nVoxels; - for (int h = 0; h < 3; ++h) { - m_minBBPts[h] = m_minBBVoxels[h] * m_scale + m_minBB[h]; - m_maxBBPts[h] = m_maxBBVoxels[h] * m_scale + m_minBB[h]; - m_barycenter[h] = (short)(bary[h] + 0.5); - } -} -void VoxelSet::ComputeConvexHull(Mesh& meshCH, const size_t sampling) const -{ - const size_t CLUSTER_SIZE = 65536; - const size_t nVoxels = m_voxels.Size(); - if (nVoxels == 0) - return; - - SArray > cpoints; - - Vec3* points = new Vec3[CLUSTER_SIZE]; - size_t p = 0; - size_t s = 0; - short i, j, k; - while (p < nVoxels) { - size_t q = 0; - while (q < CLUSTER_SIZE && p < nVoxels) { - if (m_voxels[p].m_data == PRIMITIVE_ON_SURFACE) { - ++s; - if (s == sampling) { - s = 0; - i = m_voxels[p].m_coord[0]; - j = m_voxels[p].m_coord[1]; - k = m_voxels[p].m_coord[2]; - Vec3 p0((i - 0.5) * m_scale, (j - 0.5) * m_scale, (k - 0.5) * m_scale); - Vec3 p1((i + 0.5) * m_scale, (j - 0.5) * m_scale, (k - 0.5) * m_scale); - Vec3 p2((i + 0.5) * m_scale, (j + 0.5) * m_scale, (k - 0.5) * m_scale); - Vec3 p3((i - 0.5) * m_scale, (j + 0.5) * m_scale, (k - 0.5) * m_scale); - Vec3 p4((i - 0.5) * m_scale, (j - 0.5) * m_scale, (k + 0.5) * m_scale); - Vec3 p5((i + 0.5) * m_scale, (j - 0.5) * m_scale, (k + 0.5) * m_scale); - Vec3 p6((i + 0.5) * m_scale, (j + 0.5) * m_scale, (k + 0.5) * m_scale); - Vec3 p7((i - 0.5) * m_scale, (j + 0.5) * m_scale, (k + 0.5) * m_scale); - points[q++] = p0 + m_minBB; - points[q++] = p1 + m_minBB; - points[q++] = p2 + m_minBB; - points[q++] = p3 + m_minBB; - points[q++] = p4 + m_minBB; - points[q++] = p5 + m_minBB; - points[q++] = p6 + m_minBB; - points[q++] = p7 + m_minBB; - } - } - ++p; - } - btConvexHullComputer ch; - ch.compute((double*)points, 3 * sizeof(double), (int)q, -1.0, -1.0); - for (int v = 0; v < ch.vertices.size(); v++) { - cpoints.PushBack(Vec3(ch.vertices[v].getX(), ch.vertices[v].getY(), ch.vertices[v].getZ())); - } - } - delete[] points; - - points = cpoints.Data(); - btConvexHullComputer ch; - ch.compute((double*)points, 3 * sizeof(double), (int)cpoints.Size(), -1.0, -1.0); - meshCH.ResizePoints(0); - meshCH.ResizeTriangles(0); - for (int v = 0; v < ch.vertices.size(); v++) { - meshCH.AddPoint(Vec3(ch.vertices[v].getX(), ch.vertices[v].getY(), ch.vertices[v].getZ())); - } - const int nt = ch.faces.size(); - for (int t = 0; t < nt; ++t) { - const btConvexHullComputer::Edge* sourceEdge = &(ch.edges[ch.faces[t]]); - int a = sourceEdge->getSourceVertex(); - int b = sourceEdge->getTargetVertex(); - const btConvexHullComputer::Edge* edge = sourceEdge->getNextEdgeOfFace(); - int c = edge->getTargetVertex(); - while (c != a) { - meshCH.AddTriangle(Vec3(a, b, c)); - edge = edge->getNextEdgeOfFace(); - b = c; - c = edge->getTargetVertex(); - } - } -} -void VoxelSet::GetPoints(const Voxel& voxel, - Vec3* const pts) const -{ - short i = voxel.m_coord[0]; - short j = voxel.m_coord[1]; - short k = voxel.m_coord[2]; - pts[0][0] = (i - 0.5) * m_scale + m_minBB[0]; - pts[1][0] = (i + 0.5) * m_scale + m_minBB[0]; - pts[2][0] = (i + 0.5) * m_scale + m_minBB[0]; - pts[3][0] = (i - 0.5) * m_scale + m_minBB[0]; - pts[4][0] = (i - 0.5) * m_scale + m_minBB[0]; - pts[5][0] = (i + 0.5) * m_scale + m_minBB[0]; - pts[6][0] = (i + 0.5) * m_scale + m_minBB[0]; - pts[7][0] = (i - 0.5) * m_scale + m_minBB[0]; - pts[0][1] = (j - 0.5) * m_scale + m_minBB[1]; - pts[1][1] = (j - 0.5) * m_scale + m_minBB[1]; - pts[2][1] = (j + 0.5) * m_scale + m_minBB[1]; - pts[3][1] = (j + 0.5) * m_scale + m_minBB[1]; - pts[4][1] = (j - 0.5) * m_scale + m_minBB[1]; - pts[5][1] = (j - 0.5) * m_scale + m_minBB[1]; - pts[6][1] = (j + 0.5) * m_scale + m_minBB[1]; - pts[7][1] = (j + 0.5) * m_scale + m_minBB[1]; - pts[0][2] = (k - 0.5) * m_scale + m_minBB[2]; - pts[1][2] = (k - 0.5) * m_scale + m_minBB[2]; - pts[2][2] = (k - 0.5) * m_scale + m_minBB[2]; - pts[3][2] = (k - 0.5) * m_scale + m_minBB[2]; - pts[4][2] = (k + 0.5) * m_scale + m_minBB[2]; - pts[5][2] = (k + 0.5) * m_scale + m_minBB[2]; - pts[6][2] = (k + 0.5) * m_scale + m_minBB[2]; - pts[7][2] = (k + 0.5) * m_scale + m_minBB[2]; -} -void VoxelSet::Intersect(const Plane& plane, - SArray >* const positivePts, - SArray >* const negativePts, - const size_t sampling) const -{ - const size_t nVoxels = m_voxels.Size(); - if (nVoxels == 0) - return; - const double d0 = m_scale; - double d; - Vec3 pts[8]; - Vec3 pt; - Voxel voxel; - size_t sp = 0; - size_t sn = 0; - for (size_t v = 0; v < nVoxels; ++v) { - voxel = m_voxels[v]; - pt = GetPoint(voxel); - d = plane.m_a * pt[0] + plane.m_b * pt[1] + plane.m_c * pt[2] + plane.m_d; - // if (d >= 0.0 && d <= d0) positivePts->PushBack(pt); - // else if (d < 0.0 && -d <= d0) negativePts->PushBack(pt); - if (d >= 0.0) { - if (d <= d0) { - GetPoints(voxel, pts); - for (int k = 0; k < 8; ++k) { - positivePts->PushBack(pts[k]); - } - } - else { - if (++sp == sampling) { - // positivePts->PushBack(pt); - GetPoints(voxel, pts); - for (int k = 0; k < 8; ++k) { - positivePts->PushBack(pts[k]); - } - sp = 0; - } - } - } - else { - if (-d <= d0) { - GetPoints(voxel, pts); - for (int k = 0; k < 8; ++k) { - negativePts->PushBack(pts[k]); - } - } - else { - if (++sn == sampling) { - // negativePts->PushBack(pt); - GetPoints(voxel, pts); - for (int k = 0; k < 8; ++k) { - negativePts->PushBack(pts[k]); - } - sn = 0; - } - } - } - } -} -void VoxelSet::ComputeExteriorPoints(const Plane& plane, - const Mesh& mesh, - SArray >* const exteriorPts) const -{ - const size_t nVoxels = m_voxels.Size(); - if (nVoxels == 0) - return; - double d; - Vec3 pt; - Vec3 pts[8]; - Voxel voxel; - for (size_t v = 0; v < nVoxels; ++v) { - voxel = m_voxels[v]; - pt = GetPoint(voxel); - d = plane.m_a * pt[0] + plane.m_b * pt[1] + plane.m_c * pt[2] + plane.m_d; - if (d >= 0.0) { - if (!mesh.IsInside(pt)) { - GetPoints(voxel, pts); - for (int k = 0; k < 8; ++k) { - exteriorPts->PushBack(pts[k]); - } - } - } - } -} -void VoxelSet::ComputeClippedVolumes(const Plane& plane, - double& positiveVolume, - double& negativeVolume) const -{ - negativeVolume = 0.0; - positiveVolume = 0.0; - const size_t nVoxels = m_voxels.Size(); - if (nVoxels == 0) - return; - double d; - Vec3 pt; - size_t nPositiveVoxels = 0; - for (size_t v = 0; v < nVoxels; ++v) { - pt = GetPoint(m_voxels[v]); - d = plane.m_a * pt[0] + plane.m_b * pt[1] + plane.m_c * pt[2] + plane.m_d; - nPositiveVoxels += (d >= 0.0); - } - size_t nNegativeVoxels = nVoxels - nPositiveVoxels; - positiveVolume = m_unitVolume * nPositiveVoxels; - negativeVolume = m_unitVolume * nNegativeVoxels; -} -void VoxelSet::SelectOnSurface(PrimitiveSet* const onSurfP) const -{ - VoxelSet* const onSurf = (VoxelSet*)onSurfP; - const size_t nVoxels = m_voxels.Size(); - if (nVoxels == 0) - return; - - for (int h = 0; h < 3; ++h) { - onSurf->m_minBB[h] = m_minBB[h]; - } - onSurf->m_voxels.Resize(0); - onSurf->m_scale = m_scale; - onSurf->m_unitVolume = m_unitVolume; - onSurf->m_numVoxelsOnSurface = 0; - onSurf->m_numVoxelsInsideSurface = 0; - Voxel voxel; - for (size_t v = 0; v < nVoxels; ++v) { - voxel = m_voxels[v]; - if (voxel.m_data == PRIMITIVE_ON_SURFACE) { - onSurf->m_voxels.PushBack(voxel); - ++onSurf->m_numVoxelsOnSurface; - } - } -} -void VoxelSet::Clip(const Plane& plane, - PrimitiveSet* const positivePartP, - PrimitiveSet* const negativePartP) const -{ - VoxelSet* const positivePart = (VoxelSet*)positivePartP; - VoxelSet* const negativePart = (VoxelSet*)negativePartP; - const size_t nVoxels = m_voxels.Size(); - if (nVoxels == 0) - return; - - for (int h = 0; h < 3; ++h) { - negativePart->m_minBB[h] = positivePart->m_minBB[h] = m_minBB[h]; - } - positivePart->m_voxels.Resize(0); - negativePart->m_voxels.Resize(0); - positivePart->m_voxels.Allocate(nVoxels); - negativePart->m_voxels.Allocate(nVoxels); - negativePart->m_scale = positivePart->m_scale = m_scale; - negativePart->m_unitVolume = positivePart->m_unitVolume = m_unitVolume; - negativePart->m_numVoxelsOnSurface = positivePart->m_numVoxelsOnSurface = 0; - negativePart->m_numVoxelsInsideSurface = positivePart->m_numVoxelsInsideSurface = 0; - - double d; - Vec3 pt; - Voxel voxel; - const double d0 = m_scale; - for (size_t v = 0; v < nVoxels; ++v) { - voxel = m_voxels[v]; - pt = GetPoint(voxel); - d = plane.m_a * pt[0] + plane.m_b * pt[1] + plane.m_c * pt[2] + plane.m_d; - if (d >= 0.0) { - if (voxel.m_data == PRIMITIVE_ON_SURFACE || d <= d0) { - voxel.m_data = PRIMITIVE_ON_SURFACE; - positivePart->m_voxels.PushBack(voxel); - ++positivePart->m_numVoxelsOnSurface; - } - else { - positivePart->m_voxels.PushBack(voxel); - ++positivePart->m_numVoxelsInsideSurface; - } - } - else { - if (voxel.m_data == PRIMITIVE_ON_SURFACE || -d <= d0) { - voxel.m_data = PRIMITIVE_ON_SURFACE; - negativePart->m_voxels.PushBack(voxel); - ++negativePart->m_numVoxelsOnSurface; - } - else { - negativePart->m_voxels.PushBack(voxel); - ++negativePart->m_numVoxelsInsideSurface; - } - } - } -} -void VoxelSet::Convert(Mesh& mesh, const VOXEL_VALUE value) const -{ - const size_t nVoxels = m_voxels.Size(); - if (nVoxels == 0) - return; - Voxel voxel; - Vec3 pts[8]; - for (size_t v = 0; v < nVoxels; ++v) { - voxel = m_voxels[v]; - if (voxel.m_data == value) { - GetPoints(voxel, pts); - int s = (int)mesh.GetNPoints(); - for (int k = 0; k < 8; ++k) { - mesh.AddPoint(pts[k]); - } - mesh.AddTriangle(Vec3(s + 0, s + 2, s + 1)); - mesh.AddTriangle(Vec3(s + 0, s + 3, s + 2)); - mesh.AddTriangle(Vec3(s + 4, s + 5, s + 6)); - mesh.AddTriangle(Vec3(s + 4, s + 6, s + 7)); - mesh.AddTriangle(Vec3(s + 7, s + 6, s + 2)); - mesh.AddTriangle(Vec3(s + 7, s + 2, s + 3)); - mesh.AddTriangle(Vec3(s + 4, s + 1, s + 5)); - mesh.AddTriangle(Vec3(s + 4, s + 0, s + 1)); - mesh.AddTriangle(Vec3(s + 6, s + 5, s + 1)); - mesh.AddTriangle(Vec3(s + 6, s + 1, s + 2)); - mesh.AddTriangle(Vec3(s + 7, s + 0, s + 4)); - mesh.AddTriangle(Vec3(s + 7, s + 3, s + 0)); - } - } -} -void VoxelSet::ComputePrincipalAxes() -{ - const size_t nVoxels = m_voxels.Size(); - if (nVoxels == 0) - return; - m_barycenterPCA[0] = m_barycenterPCA[1] = m_barycenterPCA[2] = 0.0; - for (size_t v = 0; v < nVoxels; ++v) { - Voxel& voxel = m_voxels[v]; - m_barycenterPCA[0] += voxel.m_coord[0]; - m_barycenterPCA[1] += voxel.m_coord[1]; - m_barycenterPCA[2] += voxel.m_coord[2]; - } - m_barycenterPCA /= (double)nVoxels; - - double covMat[3][3] = { { 0.0, 0.0, 0.0 }, - { 0.0, 0.0, 0.0 }, - { 0.0, 0.0, 0.0 } }; - double x, y, z; - for (size_t v = 0; v < nVoxels; ++v) { - Voxel& voxel = m_voxels[v]; - x = voxel.m_coord[0] - m_barycenter[0]; - y = voxel.m_coord[1] - m_barycenter[1]; - z = voxel.m_coord[2] - m_barycenter[2]; - covMat[0][0] += x * x; - covMat[1][1] += y * y; - covMat[2][2] += z * z; - covMat[0][1] += x * y; - covMat[0][2] += x * z; - covMat[1][2] += y * z; - } - covMat[0][0] /= nVoxels; - covMat[1][1] /= nVoxels; - covMat[2][2] /= nVoxels; - covMat[0][1] /= nVoxels; - covMat[0][2] /= nVoxels; - covMat[1][2] /= nVoxels; - covMat[1][0] = covMat[0][1]; - covMat[2][0] = covMat[0][2]; - covMat[2][1] = covMat[1][2]; - Diagonalize(covMat, m_Q, m_D); -} -Volume::Volume() -{ - m_dim[0] = m_dim[1] = m_dim[2] = 0; - m_minBB[0] = m_minBB[1] = m_minBB[2] = 0.0; - m_maxBB[0] = m_maxBB[1] = m_maxBB[2] = 1.0; - m_numVoxelsOnSurface = 0; - m_numVoxelsInsideSurface = 0; - m_numVoxelsOutsideSurface = 0; - m_scale = 1.0; - m_data = 0; -} -Volume::~Volume(void) -{ - delete[] m_data; -} -void Volume::Allocate() -{ - delete[] m_data; - size_t size = m_dim[0] * m_dim[1] * m_dim[2]; - m_data = new unsigned char[size]; - memset(m_data, PRIMITIVE_UNDEFINED, sizeof(unsigned char) * size); -} -void Volume::Free() -{ - delete[] m_data; - m_data = 0; -} -void Volume::FillOutsideSurface(const size_t i0, - const size_t j0, - const size_t k0, - const size_t i1, - const size_t j1, - const size_t k1) -{ - const short neighbours[6][3] = { { 1, 0, 0 }, - { 0, 1, 0 }, - { 0, 0, 1 }, - { -1, 0, 0 }, - { 0, -1, 0 }, - { 0, 0, -1 } }; - std::queue > fifo; - Vec3 current; - short a, b, c; - for (size_t i = i0; i < i1; ++i) { - for (size_t j = j0; j < j1; ++j) { - for (size_t k = k0; k < k1; ++k) { - - if (GetVoxel(i, j, k) == PRIMITIVE_UNDEFINED) { - current[0] = (short)i; - current[1] = (short)j; - current[2] = (short)k; - fifo.push(current); - GetVoxel(current[0], current[1], current[2]) = PRIMITIVE_OUTSIDE_SURFACE; - ++m_numVoxelsOutsideSurface; - while (fifo.size() > 0) { - current = fifo.front(); - fifo.pop(); - for (int h = 0; h < 6; ++h) { - a = current[0] + neighbours[h][0]; - b = current[1] + neighbours[h][1]; - c = current[2] + neighbours[h][2]; - if (a < 0 || a >= (int)m_dim[0] || b < 0 || b >= (int)m_dim[1] || c < 0 || c >= (int)m_dim[2]) { - continue; - } - unsigned char& v = GetVoxel(a, b, c); - if (v == PRIMITIVE_UNDEFINED) { - v = PRIMITIVE_OUTSIDE_SURFACE; - ++m_numVoxelsOutsideSurface; - fifo.push(Vec3(a, b, c)); - } - } - } - } - } - } - } -} -void Volume::FillInsideSurface() -{ - const size_t i0 = m_dim[0]; - const size_t j0 = m_dim[1]; - const size_t k0 = m_dim[2]; - for (size_t i = 0; i < i0; ++i) { - for (size_t j = 0; j < j0; ++j) { - for (size_t k = 0; k < k0; ++k) { - unsigned char& v = GetVoxel(i, j, k); - if (v == PRIMITIVE_UNDEFINED) { - v = PRIMITIVE_INSIDE_SURFACE; - ++m_numVoxelsInsideSurface; - } - } - } - } -} -void Volume::Convert(Mesh& mesh, const VOXEL_VALUE value) const -{ - const size_t i0 = m_dim[0]; - const size_t j0 = m_dim[1]; - const size_t k0 = m_dim[2]; - for (size_t i = 0; i < i0; ++i) { - for (size_t j = 0; j < j0; ++j) { - for (size_t k = 0; k < k0; ++k) { - const unsigned char& voxel = GetVoxel(i, j, k); - if (voxel == value) { - Vec3 p0((i - 0.5) * m_scale, (j - 0.5) * m_scale, (k - 0.5) * m_scale); - Vec3 p1((i + 0.5) * m_scale, (j - 0.5) * m_scale, (k - 0.5) * m_scale); - Vec3 p2((i + 0.5) * m_scale, (j + 0.5) * m_scale, (k - 0.5) * m_scale); - Vec3 p3((i - 0.5) * m_scale, (j + 0.5) * m_scale, (k - 0.5) * m_scale); - Vec3 p4((i - 0.5) * m_scale, (j - 0.5) * m_scale, (k + 0.5) * m_scale); - Vec3 p5((i + 0.5) * m_scale, (j - 0.5) * m_scale, (k + 0.5) * m_scale); - Vec3 p6((i + 0.5) * m_scale, (j + 0.5) * m_scale, (k + 0.5) * m_scale); - Vec3 p7((i - 0.5) * m_scale, (j + 0.5) * m_scale, (k + 0.5) * m_scale); - int s = (int)mesh.GetNPoints(); - mesh.AddPoint(p0 + m_minBB); - mesh.AddPoint(p1 + m_minBB); - mesh.AddPoint(p2 + m_minBB); - mesh.AddPoint(p3 + m_minBB); - mesh.AddPoint(p4 + m_minBB); - mesh.AddPoint(p5 + m_minBB); - mesh.AddPoint(p6 + m_minBB); - mesh.AddPoint(p7 + m_minBB); - mesh.AddTriangle(Vec3(s + 0, s + 2, s + 1)); - mesh.AddTriangle(Vec3(s + 0, s + 3, s + 2)); - mesh.AddTriangle(Vec3(s + 4, s + 5, s + 6)); - mesh.AddTriangle(Vec3(s + 4, s + 6, s + 7)); - mesh.AddTriangle(Vec3(s + 7, s + 6, s + 2)); - mesh.AddTriangle(Vec3(s + 7, s + 2, s + 3)); - mesh.AddTriangle(Vec3(s + 4, s + 1, s + 5)); - mesh.AddTriangle(Vec3(s + 4, s + 0, s + 1)); - mesh.AddTriangle(Vec3(s + 6, s + 5, s + 1)); - mesh.AddTriangle(Vec3(s + 6, s + 1, s + 2)); - mesh.AddTriangle(Vec3(s + 7, s + 0, s + 4)); - mesh.AddTriangle(Vec3(s + 7, s + 3, s + 0)); - } - } - } - } -} -void Volume::Convert(VoxelSet& vset) const -{ - for (int h = 0; h < 3; ++h) { - vset.m_minBB[h] = m_minBB[h]; - } - vset.m_voxels.Allocate(m_numVoxelsInsideSurface + m_numVoxelsOnSurface); - vset.m_scale = m_scale; - vset.m_unitVolume = m_scale * m_scale * m_scale; - const short i0 = (short)m_dim[0]; - const short j0 = (short)m_dim[1]; - const short k0 = (short)m_dim[2]; - Voxel voxel; - vset.m_numVoxelsOnSurface = 0; - vset.m_numVoxelsInsideSurface = 0; - for (short i = 0; i < i0; ++i) { - for (short j = 0; j < j0; ++j) { - for (short k = 0; k < k0; ++k) { - const unsigned char& value = GetVoxel(i, j, k); - if (value == PRIMITIVE_INSIDE_SURFACE) { - voxel.m_coord[0] = i; - voxel.m_coord[1] = j; - voxel.m_coord[2] = k; - voxel.m_data = PRIMITIVE_INSIDE_SURFACE; - vset.m_voxels.PushBack(voxel); - ++vset.m_numVoxelsInsideSurface; - } - else if (value == PRIMITIVE_ON_SURFACE) { - voxel.m_coord[0] = i; - voxel.m_coord[1] = j; - voxel.m_coord[2] = k; - voxel.m_data = PRIMITIVE_ON_SURFACE; - vset.m_voxels.PushBack(voxel); - ++vset.m_numVoxelsOnSurface; - } - } - } - } -} - -void Volume::Convert(TetrahedronSet& tset) const -{ - tset.m_tetrahedra.Allocate(5 * (m_numVoxelsInsideSurface + m_numVoxelsOnSurface)); - tset.m_scale = m_scale; - const short i0 = (short)m_dim[0]; - const short j0 = (short)m_dim[1]; - const short k0 = (short)m_dim[2]; - tset.m_numTetrahedraOnSurface = 0; - tset.m_numTetrahedraInsideSurface = 0; - Tetrahedron tetrahedron; - for (short i = 0; i < i0; ++i) { - for (short j = 0; j < j0; ++j) { - for (short k = 0; k < k0; ++k) { - const unsigned char& value = GetVoxel(i, j, k); - if (value == PRIMITIVE_INSIDE_SURFACE || value == PRIMITIVE_ON_SURFACE) { - tetrahedron.m_data = value; - Vec3 p1((i - 0.5) * m_scale + m_minBB[0], (j - 0.5) * m_scale + m_minBB[1], (k - 0.5) * m_scale + m_minBB[2]); - Vec3 p2((i + 0.5) * m_scale + m_minBB[0], (j - 0.5) * m_scale + m_minBB[1], (k - 0.5) * m_scale + m_minBB[2]); - Vec3 p3((i + 0.5) * m_scale + m_minBB[0], (j + 0.5) * m_scale + m_minBB[1], (k - 0.5) * m_scale + m_minBB[2]); - Vec3 p4((i - 0.5) * m_scale + m_minBB[0], (j + 0.5) * m_scale + m_minBB[1], (k - 0.5) * m_scale + m_minBB[2]); - Vec3 p5((i - 0.5) * m_scale + m_minBB[0], (j - 0.5) * m_scale + m_minBB[1], (k + 0.5) * m_scale + m_minBB[2]); - Vec3 p6((i + 0.5) * m_scale + m_minBB[0], (j - 0.5) * m_scale + m_minBB[1], (k + 0.5) * m_scale + m_minBB[2]); - Vec3 p7((i + 0.5) * m_scale + m_minBB[0], (j + 0.5) * m_scale + m_minBB[1], (k + 0.5) * m_scale + m_minBB[2]); - Vec3 p8((i - 0.5) * m_scale + m_minBB[0], (j + 0.5) * m_scale + m_minBB[1], (k + 0.5) * m_scale + m_minBB[2]); - - tetrahedron.m_pts[0] = p2; - tetrahedron.m_pts[1] = p4; - tetrahedron.m_pts[2] = p7; - tetrahedron.m_pts[3] = p5; - tset.m_tetrahedra.PushBack(tetrahedron); - - tetrahedron.m_pts[0] = p6; - tetrahedron.m_pts[1] = p2; - tetrahedron.m_pts[2] = p7; - tetrahedron.m_pts[3] = p5; - tset.m_tetrahedra.PushBack(tetrahedron); - - tetrahedron.m_pts[0] = p3; - tetrahedron.m_pts[1] = p4; - tetrahedron.m_pts[2] = p7; - tetrahedron.m_pts[3] = p2; - tset.m_tetrahedra.PushBack(tetrahedron); - - tetrahedron.m_pts[0] = p1; - tetrahedron.m_pts[1] = p4; - tetrahedron.m_pts[2] = p2; - tetrahedron.m_pts[3] = p5; - tset.m_tetrahedra.PushBack(tetrahedron); - - tetrahedron.m_pts[0] = p8; - tetrahedron.m_pts[1] = p5; - tetrahedron.m_pts[2] = p7; - tetrahedron.m_pts[3] = p4; - tset.m_tetrahedra.PushBack(tetrahedron); - if (value == PRIMITIVE_INSIDE_SURFACE) { - tset.m_numTetrahedraInsideSurface += 5; - } - else { - tset.m_numTetrahedraOnSurface += 5; - } - } - } - } - } -} - -void Volume::AlignToPrincipalAxes(double (&rot)[3][3]) const -{ - const short i0 = (short)m_dim[0]; - const short j0 = (short)m_dim[1]; - const short k0 = (short)m_dim[2]; - Vec3 barycenter(0.0); - size_t nVoxels = 0; - for (short i = 0; i < i0; ++i) { - for (short j = 0; j < j0; ++j) { - for (short k = 0; k < k0; ++k) { - const unsigned char& value = GetVoxel(i, j, k); - if (value == PRIMITIVE_INSIDE_SURFACE || value == PRIMITIVE_ON_SURFACE) { - barycenter[0] += i; - barycenter[1] += j; - barycenter[2] += k; - ++nVoxels; - } - } - } - } - barycenter /= (double)nVoxels; - - double covMat[3][3] = { { 0.0, 0.0, 0.0 }, - { 0.0, 0.0, 0.0 }, - { 0.0, 0.0, 0.0 } }; - double x, y, z; - for (short i = 0; i < i0; ++i) { - for (short j = 0; j < j0; ++j) { - for (short k = 0; k < k0; ++k) { - const unsigned char& value = GetVoxel(i, j, k); - if (value == PRIMITIVE_INSIDE_SURFACE || value == PRIMITIVE_ON_SURFACE) { - x = i - barycenter[0]; - y = j - barycenter[1]; - z = k - barycenter[2]; - covMat[0][0] += x * x; - covMat[1][1] += y * y; - covMat[2][2] += z * z; - covMat[0][1] += x * y; - covMat[0][2] += x * z; - covMat[1][2] += y * z; - } - } - } - } - covMat[1][0] = covMat[0][1]; - covMat[2][0] = covMat[0][2]; - covMat[2][1] = covMat[1][2]; - double D[3][3]; - Diagonalize(covMat, rot, D); -} -TetrahedronSet::TetrahedronSet() -{ - m_minBB[0] = m_minBB[1] = m_minBB[2] = 0.0; - m_maxBB[0] = m_maxBB[1] = m_maxBB[2] = 1.0; - m_barycenter[0] = m_barycenter[1] = m_barycenter[2] = 0.0; - m_scale = 1.0; - m_numTetrahedraOnSurface = 0; - m_numTetrahedraInsideSurface = 0; - memset(m_Q, 0, sizeof(double) * 9); - memset(m_D, 0, sizeof(double) * 9); -} -TetrahedronSet::~TetrahedronSet(void) -{ -} -void TetrahedronSet::ComputeBB() -{ - const size_t nTetrahedra = m_tetrahedra.Size(); - if (nTetrahedra == 0) - return; - - for (int h = 0; h < 3; ++h) { - m_minBB[h] = m_maxBB[h] = m_tetrahedra[0].m_pts[0][h]; - m_barycenter[h] = 0.0; - } - for (size_t p = 0; p < nTetrahedra; ++p) { - for (int i = 0; i < 4; ++i) { - for (int h = 0; h < 3; ++h) { - if (m_minBB[h] > m_tetrahedra[p].m_pts[i][h]) - m_minBB[h] = m_tetrahedra[p].m_pts[i][h]; - if (m_maxBB[h] < m_tetrahedra[p].m_pts[i][h]) - m_maxBB[h] = m_tetrahedra[p].m_pts[i][h]; - m_barycenter[h] += m_tetrahedra[p].m_pts[i][h]; - } - } - } - m_barycenter /= (double)(4 * nTetrahedra); -} -void TetrahedronSet::ComputeConvexHull(Mesh& meshCH, const size_t sampling) const -{ - const size_t CLUSTER_SIZE = 65536; - const size_t nTetrahedra = m_tetrahedra.Size(); - if (nTetrahedra == 0) - return; - - SArray > cpoints; - - Vec3* points = new Vec3[CLUSTER_SIZE]; - size_t p = 0; - while (p < nTetrahedra) { - size_t q = 0; - size_t s = 0; - while (q < CLUSTER_SIZE && p < nTetrahedra) { - if (m_tetrahedra[p].m_data == PRIMITIVE_ON_SURFACE) { - ++s; - if (s == sampling) { - s = 0; - for (int a = 0; a < 4; ++a) { - points[q++] = m_tetrahedra[p].m_pts[a]; - for (int xx = 0; xx < 3; ++xx) { - assert(m_tetrahedra[p].m_pts[a][xx] + EPS >= m_minBB[xx]); - assert(m_tetrahedra[p].m_pts[a][xx] <= m_maxBB[xx] + EPS); - } - } - } - } - ++p; - } - btConvexHullComputer ch; - ch.compute((double*)points, 3 * sizeof(double), (int)q, -1.0, -1.0); - for (int v = 0; v < ch.vertices.size(); v++) { - cpoints.PushBack(Vec3(ch.vertices[v].getX(), ch.vertices[v].getY(), ch.vertices[v].getZ())); - } - } - delete[] points; - - points = cpoints.Data(); - btConvexHullComputer ch; - ch.compute((double*)points, 3 * sizeof(double), (int)cpoints.Size(), -1.0, -1.0); - meshCH.ResizePoints(0); - meshCH.ResizeTriangles(0); - for (int v = 0; v < ch.vertices.size(); v++) { - meshCH.AddPoint(Vec3(ch.vertices[v].getX(), ch.vertices[v].getY(), ch.vertices[v].getZ())); - } - const int nt = ch.faces.size(); - for (int t = 0; t < nt; ++t) { - const btConvexHullComputer::Edge* sourceEdge = &(ch.edges[ch.faces[t]]); - int a = sourceEdge->getSourceVertex(); - int b = sourceEdge->getTargetVertex(); - const btConvexHullComputer::Edge* edge = sourceEdge->getNextEdgeOfFace(); - int c = edge->getTargetVertex(); - while (c != a) { - meshCH.AddTriangle(Vec3(a, b, c)); - edge = edge->getNextEdgeOfFace(); - b = c; - c = edge->getTargetVertex(); - } - } -} -inline bool TetrahedronSet::Add(Tetrahedron& tetrahedron) -{ - double v = ComputeVolume4(tetrahedron.m_pts[0], tetrahedron.m_pts[1], tetrahedron.m_pts[2], tetrahedron.m_pts[3]); - - const double EPS = 0.0000000001; - if (fabs(v) < EPS) { - return false; - } - else if (v < 0.0) { - Vec3 tmp = tetrahedron.m_pts[0]; - tetrahedron.m_pts[0] = tetrahedron.m_pts[1]; - tetrahedron.m_pts[1] = tmp; - } - - for (int a = 0; a < 4; ++a) { - for (int xx = 0; xx < 3; ++xx) { - assert(tetrahedron.m_pts[a][xx] + EPS >= m_minBB[xx]); - assert(tetrahedron.m_pts[a][xx] <= m_maxBB[xx] + EPS); - } - } - m_tetrahedra.PushBack(tetrahedron); - return true; -} - -void TetrahedronSet::AddClippedTetrahedra(const Vec3 (&pts)[10], const int nPts) -{ - const int tetF[4][3] = { { 0, 1, 2 }, { 2, 1, 3 }, { 3, 1, 0 }, { 3, 0, 2 } }; - if (nPts < 4) { - return; - } - else if (nPts == 4) { - Tetrahedron tetrahedron; - tetrahedron.m_data = PRIMITIVE_ON_SURFACE; - tetrahedron.m_pts[0] = pts[0]; - tetrahedron.m_pts[1] = pts[1]; - tetrahedron.m_pts[2] = pts[2]; - tetrahedron.m_pts[3] = pts[3]; - if (Add(tetrahedron)) { - ++m_numTetrahedraOnSurface; - } - } - else if (nPts == 5) { - const int tet[15][4] = { - { 0, 1, 2, 3 }, { 1, 2, 3, 4 }, { 0, 2, 3, 4 }, { 0, 1, 3, 4 }, { 0, 1, 2, 4 }, - }; - const int rem[5] = { 4, 0, 1, 2, 3 }; - double maxVol = 0.0; - int h0 = -1; - Tetrahedron tetrahedron0; - tetrahedron0.m_data = PRIMITIVE_ON_SURFACE; - for (int h = 0; h < 5; ++h) { - double v = ComputeVolume4(pts[tet[h][0]], pts[tet[h][1]], pts[tet[h][2]], pts[tet[h][3]]); - if (v > maxVol) { - h0 = h; - tetrahedron0.m_pts[0] = pts[tet[h][0]]; - tetrahedron0.m_pts[1] = pts[tet[h][1]]; - tetrahedron0.m_pts[2] = pts[tet[h][2]]; - tetrahedron0.m_pts[3] = pts[tet[h][3]]; - maxVol = v; - } - else if (-v > maxVol) { - h0 = h; - tetrahedron0.m_pts[0] = pts[tet[h][1]]; - tetrahedron0.m_pts[1] = pts[tet[h][0]]; - tetrahedron0.m_pts[2] = pts[tet[h][2]]; - tetrahedron0.m_pts[3] = pts[tet[h][3]]; - maxVol = -v; - } - } - if (h0 == -1) - return; - if (Add(tetrahedron0)) { - ++m_numTetrahedraOnSurface; - } - else { - return; - } - int a = rem[h0]; - maxVol = 0.0; - int h1 = -1; - Tetrahedron tetrahedron1; - tetrahedron1.m_data = PRIMITIVE_ON_SURFACE; - for (int h = 0; h < 4; ++h) { - double v = ComputeVolume4(pts[a], tetrahedron0.m_pts[tetF[h][0]], tetrahedron0.m_pts[tetF[h][1]], tetrahedron0.m_pts[tetF[h][2]]); - if (v > maxVol) { - h1 = h; - tetrahedron1.m_pts[0] = pts[a]; - tetrahedron1.m_pts[1] = tetrahedron0.m_pts[tetF[h][0]]; - tetrahedron1.m_pts[2] = tetrahedron0.m_pts[tetF[h][1]]; - tetrahedron1.m_pts[3] = tetrahedron0.m_pts[tetF[h][2]]; - maxVol = v; - } - } - if (h1 == -1 && Add(tetrahedron1)) { - ++m_numTetrahedraOnSurface; - } - } - else if (nPts == 6) { - - const int tet[15][4] = { { 2, 3, 4, 5 }, { 1, 3, 4, 5 }, { 1, 2, 4, 5 }, { 1, 2, 3, 5 }, { 1, 2, 3, 4 }, - { 0, 3, 4, 5 }, { 0, 2, 4, 5 }, { 0, 2, 3, 5 }, { 0, 2, 3, 4 }, { 0, 1, 4, 5 }, - { 0, 1, 3, 5 }, { 0, 1, 3, 4 }, { 0, 1, 2, 5 }, { 0, 1, 2, 4 }, { 0, 1, 2, 3 } }; - const int rem[15][2] = { { 0, 1 }, { 0, 2 }, { 0, 3 }, { 0, 4 }, { 0, 5 }, - { 1, 2 }, { 1, 3 }, { 1, 4 }, { 1, 5 }, { 2, 3 }, - { 2, 4 }, { 2, 5 }, { 3, 4 }, { 3, 5 }, { 4, 5 } }; - double maxVol = 0.0; - int h0 = -1; - Tetrahedron tetrahedron0; - tetrahedron0.m_data = PRIMITIVE_ON_SURFACE; - for (int h = 0; h < 15; ++h) { - double v = ComputeVolume4(pts[tet[h][0]], pts[tet[h][1]], pts[tet[h][2]], pts[tet[h][3]]); - if (v > maxVol) { - h0 = h; - tetrahedron0.m_pts[0] = pts[tet[h][0]]; - tetrahedron0.m_pts[1] = pts[tet[h][1]]; - tetrahedron0.m_pts[2] = pts[tet[h][2]]; - tetrahedron0.m_pts[3] = pts[tet[h][3]]; - maxVol = v; - } - else if (-v > maxVol) { - h0 = h; - tetrahedron0.m_pts[0] = pts[tet[h][1]]; - tetrahedron0.m_pts[1] = pts[tet[h][0]]; - tetrahedron0.m_pts[2] = pts[tet[h][2]]; - tetrahedron0.m_pts[3] = pts[tet[h][3]]; - maxVol = -v; - } - } - if (h0 == -1) - return; - if (Add(tetrahedron0)) { - ++m_numTetrahedraOnSurface; - } - else { - return; - } - - int a0 = rem[h0][0]; - int a1 = rem[h0][1]; - int h1 = -1; - Tetrahedron tetrahedron1; - tetrahedron1.m_data = PRIMITIVE_ON_SURFACE; - maxVol = 0.0; - for (int h = 0; h < 4; ++h) { - double v = ComputeVolume4(pts[a0], tetrahedron0.m_pts[tetF[h][0]], tetrahedron0.m_pts[tetF[h][1]], tetrahedron0.m_pts[tetF[h][2]]); - if (v > maxVol) { - h1 = h; - tetrahedron1.m_pts[0] = pts[a0]; - tetrahedron1.m_pts[1] = tetrahedron0.m_pts[tetF[h][0]]; - tetrahedron1.m_pts[2] = tetrahedron0.m_pts[tetF[h][1]]; - tetrahedron1.m_pts[3] = tetrahedron0.m_pts[tetF[h][2]]; - maxVol = v; - } - } - if (h1 != -1 && Add(tetrahedron1)) { - ++m_numTetrahedraOnSurface; - } - else { - h1 = -1; - } - maxVol = 0.0; - int h2 = -1; - Tetrahedron tetrahedron2; - tetrahedron2.m_data = PRIMITIVE_ON_SURFACE; - for (int h = 0; h < 4; ++h) { - double v = ComputeVolume4(pts[a0], tetrahedron0.m_pts[tetF[h][0]], tetrahedron0.m_pts[tetF[h][1]], tetrahedron0.m_pts[tetF[h][2]]); - if (h == h1) - continue; - if (v > maxVol) { - h2 = h; - tetrahedron2.m_pts[0] = pts[a1]; - tetrahedron2.m_pts[1] = tetrahedron0.m_pts[tetF[h][0]]; - tetrahedron2.m_pts[2] = tetrahedron0.m_pts[tetF[h][1]]; - tetrahedron2.m_pts[3] = tetrahedron0.m_pts[tetF[h][2]]; - maxVol = v; - } - } - if (h1 != -1) { - for (int h = 0; h < 4; ++h) { - double v = ComputeVolume4(pts[a1], tetrahedron1.m_pts[tetF[h][0]], tetrahedron1.m_pts[tetF[h][1]], tetrahedron1.m_pts[tetF[h][2]]); - if (h == 1) - continue; - if (v > maxVol) { - h2 = h; - tetrahedron2.m_pts[0] = pts[a1]; - tetrahedron2.m_pts[1] = tetrahedron1.m_pts[tetF[h][0]]; - tetrahedron2.m_pts[2] = tetrahedron1.m_pts[tetF[h][1]]; - tetrahedron2.m_pts[3] = tetrahedron1.m_pts[tetF[h][2]]; - maxVol = v; - } - } - } - if (h2 != -1 && Add(tetrahedron2)) { - ++m_numTetrahedraOnSurface; - } - } - else { - assert(0); - } -} - -void TetrahedronSet::Intersect(const Plane& plane, - SArray >* const positivePts, - SArray >* const negativePts, - const size_t sampling) const -{ - const size_t nTetrahedra = m_tetrahedra.Size(); - if (nTetrahedra == 0) - return; -} -void TetrahedronSet::ComputeExteriorPoints(const Plane& plane, - const Mesh& mesh, - SArray >* const exteriorPts) const -{ -} -void TetrahedronSet::ComputeClippedVolumes(const Plane& plane, - double& positiveVolume, - double& negativeVolume) const -{ - const size_t nTetrahedra = m_tetrahedra.Size(); - if (nTetrahedra == 0) - return; -} - -void TetrahedronSet::SelectOnSurface(PrimitiveSet* const onSurfP) const -{ - TetrahedronSet* const onSurf = (TetrahedronSet*)onSurfP; - const size_t nTetrahedra = m_tetrahedra.Size(); - if (nTetrahedra == 0) - return; - onSurf->m_tetrahedra.Resize(0); - onSurf->m_scale = m_scale; - onSurf->m_numTetrahedraOnSurface = 0; - onSurf->m_numTetrahedraInsideSurface = 0; - onSurf->m_barycenter = m_barycenter; - onSurf->m_minBB = m_minBB; - onSurf->m_maxBB = m_maxBB; - for (int i = 0; i < 3; ++i) { - for (int j = 0; j < 3; ++j) { - onSurf->m_Q[i][j] = m_Q[i][j]; - onSurf->m_D[i][j] = m_D[i][j]; - } - } - Tetrahedron tetrahedron; - for (size_t v = 0; v < nTetrahedra; ++v) { - tetrahedron = m_tetrahedra[v]; - if (tetrahedron.m_data == PRIMITIVE_ON_SURFACE) { - onSurf->m_tetrahedra.PushBack(tetrahedron); - ++onSurf->m_numTetrahedraOnSurface; - } - } -} -void TetrahedronSet::Clip(const Plane& plane, - PrimitiveSet* const positivePartP, - PrimitiveSet* const negativePartP) const -{ - TetrahedronSet* const positivePart = (TetrahedronSet*)positivePartP; - TetrahedronSet* const negativePart = (TetrahedronSet*)negativePartP; - const size_t nTetrahedra = m_tetrahedra.Size(); - if (nTetrahedra == 0) - return; - positivePart->m_tetrahedra.Resize(0); - negativePart->m_tetrahedra.Resize(0); - positivePart->m_tetrahedra.Allocate(nTetrahedra); - negativePart->m_tetrahedra.Allocate(nTetrahedra); - negativePart->m_scale = positivePart->m_scale = m_scale; - negativePart->m_numTetrahedraOnSurface = positivePart->m_numTetrahedraOnSurface = 0; - negativePart->m_numTetrahedraInsideSurface = positivePart->m_numTetrahedraInsideSurface = 0; - negativePart->m_barycenter = m_barycenter; - positivePart->m_barycenter = m_barycenter; - negativePart->m_minBB = m_minBB; - positivePart->m_minBB = m_minBB; - negativePart->m_maxBB = m_maxBB; - positivePart->m_maxBB = m_maxBB; - for (int i = 0; i < 3; ++i) { - for (int j = 0; j < 3; ++j) { - negativePart->m_Q[i][j] = positivePart->m_Q[i][j] = m_Q[i][j]; - negativePart->m_D[i][j] = positivePart->m_D[i][j] = m_D[i][j]; - } - } - - Tetrahedron tetrahedron; - double delta, alpha; - int sign[4]; - int npos, nneg; - Vec3 posPts[10]; - Vec3 negPts[10]; - Vec3 P0, P1, M; - const Vec3 n(plane.m_a, plane.m_b, plane.m_c); - const int edges[6][2] = { { 0, 1 }, { 0, 2 }, { 0, 3 }, { 1, 2 }, { 1, 3 }, { 2, 3 } }; - double dist; - for (size_t v = 0; v < nTetrahedra; ++v) { - tetrahedron = m_tetrahedra[v]; - npos = nneg = 0; - for (int i = 0; i < 4; ++i) { - dist = plane.m_a * tetrahedron.m_pts[i][0] + plane.m_b * tetrahedron.m_pts[i][1] + plane.m_c * tetrahedron.m_pts[i][2] + plane.m_d; - if (dist > 0.0) { - sign[i] = 1; - posPts[npos] = tetrahedron.m_pts[i]; - ++npos; - } - else { - sign[i] = -1; - negPts[nneg] = tetrahedron.m_pts[i]; - ++nneg; - } - } - - if (npos == 4) { - positivePart->Add(tetrahedron); - if (tetrahedron.m_data == PRIMITIVE_ON_SURFACE) { - ++positivePart->m_numTetrahedraOnSurface; - } - else { - ++positivePart->m_numTetrahedraInsideSurface; - } - } - else if (nneg == 4) { - negativePart->Add(tetrahedron); - if (tetrahedron.m_data == PRIMITIVE_ON_SURFACE) { - ++negativePart->m_numTetrahedraOnSurface; - } - else { - ++negativePart->m_numTetrahedraInsideSurface; - } - } - else { - int nnew = 0; - for (int j = 0; j < 6; ++j) { - if (sign[edges[j][0]] * sign[edges[j][1]] == -1) { - P0 = tetrahedron.m_pts[edges[j][0]]; - P1 = tetrahedron.m_pts[edges[j][1]]; - delta = (P0 - P1) * n; - alpha = -(plane.m_d + (n * P1)) / delta; - assert(alpha >= 0.0 && alpha <= 1.0); - M = alpha * P0 + (1 - alpha) * P1; - for (int xx = 0; xx < 3; ++xx) { - assert(M[xx] + EPS >= m_minBB[xx]); - assert(M[xx] <= m_maxBB[xx] + EPS); - } - posPts[npos++] = M; - negPts[nneg++] = M; - ++nnew; - } - } - negativePart->AddClippedTetrahedra(negPts, nneg); - positivePart->AddClippedTetrahedra(posPts, npos); - } - } -} -void TetrahedronSet::Convert(Mesh& mesh, const VOXEL_VALUE value) const -{ - const size_t nTetrahedra = m_tetrahedra.Size(); - if (nTetrahedra == 0) - return; - for (size_t v = 0; v < nTetrahedra; ++v) { - const Tetrahedron& tetrahedron = m_tetrahedra[v]; - if (tetrahedron.m_data == value) { - int s = (int)mesh.GetNPoints(); - mesh.AddPoint(tetrahedron.m_pts[0]); - mesh.AddPoint(tetrahedron.m_pts[1]); - mesh.AddPoint(tetrahedron.m_pts[2]); - mesh.AddPoint(tetrahedron.m_pts[3]); - mesh.AddTriangle(Vec3(s + 0, s + 1, s + 2)); - mesh.AddTriangle(Vec3(s + 2, s + 1, s + 3)); - mesh.AddTriangle(Vec3(s + 3, s + 1, s + 0)); - mesh.AddTriangle(Vec3(s + 3, s + 0, s + 2)); - } - } -} -const double TetrahedronSet::ComputeVolume() const -{ - const size_t nTetrahedra = m_tetrahedra.Size(); - if (nTetrahedra == 0) - return 0.0; - double volume = 0.0; - for (size_t v = 0; v < nTetrahedra; ++v) { - const Tetrahedron& tetrahedron = m_tetrahedra[v]; - volume += fabs(ComputeVolume4(tetrahedron.m_pts[0], tetrahedron.m_pts[1], tetrahedron.m_pts[2], tetrahedron.m_pts[3])); - } - return volume / 6.0; -} -const double TetrahedronSet::ComputeMaxVolumeError() const -{ - const size_t nTetrahedra = m_tetrahedra.Size(); - if (nTetrahedra == 0) - return 0.0; - double volume = 0.0; - for (size_t v = 0; v < nTetrahedra; ++v) { - const Tetrahedron& tetrahedron = m_tetrahedra[v]; - if (tetrahedron.m_data == PRIMITIVE_ON_SURFACE) { - volume += fabs(ComputeVolume4(tetrahedron.m_pts[0], tetrahedron.m_pts[1], tetrahedron.m_pts[2], tetrahedron.m_pts[3])); - } - } - return volume / 6.0; -} -void TetrahedronSet::RevertAlignToPrincipalAxes() -{ - const size_t nTetrahedra = m_tetrahedra.Size(); - if (nTetrahedra == 0) - return; - double x, y, z; - for (size_t v = 0; v < nTetrahedra; ++v) { - Tetrahedron& tetrahedron = m_tetrahedra[v]; - for (int i = 0; i < 4; ++i) { - x = tetrahedron.m_pts[i][0] - m_barycenter[0]; - y = tetrahedron.m_pts[i][1] - m_barycenter[1]; - z = tetrahedron.m_pts[i][2] - m_barycenter[2]; - tetrahedron.m_pts[i][0] = m_Q[0][0] * x + m_Q[0][1] * y + m_Q[0][2] * z + m_barycenter[0]; - tetrahedron.m_pts[i][1] = m_Q[1][0] * x + m_Q[1][1] * y + m_Q[1][2] * z + m_barycenter[1]; - tetrahedron.m_pts[i][2] = m_Q[2][0] * x + m_Q[2][1] * y + m_Q[2][2] * z + m_barycenter[2]; - } - } - ComputeBB(); -} -void TetrahedronSet::ComputePrincipalAxes() -{ - const size_t nTetrahedra = m_tetrahedra.Size(); - if (nTetrahedra == 0) - return; - double covMat[3][3] = { { 0.0, 0.0, 0.0 }, - { 0.0, 0.0, 0.0 }, - { 0.0, 0.0, 0.0 } }; - double x, y, z; - for (size_t v = 0; v < nTetrahedra; ++v) { - Tetrahedron& tetrahedron = m_tetrahedra[v]; - for (int i = 0; i < 4; ++i) { - x = tetrahedron.m_pts[i][0] - m_barycenter[0]; - y = tetrahedron.m_pts[i][1] - m_barycenter[1]; - z = tetrahedron.m_pts[i][2] - m_barycenter[2]; - covMat[0][0] += x * x; - covMat[1][1] += y * y; - covMat[2][2] += z * z; - covMat[0][1] += x * y; - covMat[0][2] += x * z; - covMat[1][2] += y * z; - } - } - double n = nTetrahedra * 4.0; - covMat[0][0] /= n; - covMat[1][1] /= n; - covMat[2][2] /= n; - covMat[0][1] /= n; - covMat[0][2] /= n; - covMat[1][2] /= n; - covMat[1][0] = covMat[0][1]; - covMat[2][0] = covMat[0][2]; - covMat[2][1] = covMat[1][2]; - Diagonalize(covMat, m_Q, m_D); -} -void TetrahedronSet::AlignToPrincipalAxes() -{ - const size_t nTetrahedra = m_tetrahedra.Size(); - if (nTetrahedra == 0) - return; - double x, y, z; - for (size_t v = 0; v < nTetrahedra; ++v) { - Tetrahedron& tetrahedron = m_tetrahedra[v]; - for (int i = 0; i < 4; ++i) { - x = tetrahedron.m_pts[i][0] - m_barycenter[0]; - y = tetrahedron.m_pts[i][1] - m_barycenter[1]; - z = tetrahedron.m_pts[i][2] - m_barycenter[2]; - tetrahedron.m_pts[i][0] = m_Q[0][0] * x + m_Q[1][0] * y + m_Q[2][0] * z + m_barycenter[0]; - tetrahedron.m_pts[i][1] = m_Q[0][1] * x + m_Q[1][1] * y + m_Q[2][1] * z + m_barycenter[1]; - tetrahedron.m_pts[i][2] = m_Q[0][2] * x + m_Q[1][2] * y + m_Q[2][2] * z + m_barycenter[2]; - } - } - ComputeBB(); -} -} diff --git a/extern/bullet/src/Extras/VHACD/test/inc/oclHelper.h b/extern/bullet/src/Extras/VHACD/test/inc/oclHelper.h deleted file mode 100644 index ff63c3006c1c..000000000000 --- a/extern/bullet/src/Extras/VHACD/test/inc/oclHelper.h +++ /dev/null @@ -1,50 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) - All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#ifdef OPENCL_FOUND - -#pragma once -#ifndef OCL_HELPER_H -#define OCL_HELPER_H - -#include -#include - -#ifdef __MACH__ -#include -#else -#include -#endif - -class OCLHelper { -public: - OCLHelper(void){}; - ~OCLHelper(void){}; - bool InitPlatform(const unsigned int platformIndex = 0); - bool InitDevice(const unsigned int deviceIndex); - bool GetPlatformsInfo(std::vector& info, const std::string& indentation); - bool GetDevicesInfo(std::vector& info, const std::string& indentation); - cl_platform_id* GetPlatform() { return &m_platform; } - const cl_platform_id* GetPlatform() const { return &m_platform; } - cl_device_id* GetDevice() { return &m_device; } - const cl_device_id* GetDevice() const { return &m_device; } -private: - cl_platform_id m_platform; - cl_device_id m_device; - cl_int m_lastError; -}; - -#endif // OCL_HELPER_H - -#endif //OPENCL_FOUND diff --git a/extern/bullet/src/Extras/VHACD/test/src/main.cpp b/extern/bullet/src/Extras/VHACD/test/src/main.cpp deleted file mode 100644 index 1c6112339fb1..000000000000 --- a/extern/bullet/src/Extras/VHACD/test/src/main.cpp +++ /dev/null @@ -1,665 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) - All rights reserved. - - - Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - - 3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ - -#define _CRT_SECURE_NO_WARNINGS -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -//#define _CRTDBG_MAP_ALLOC - -#ifdef _CRTDBG_MAP_ALLOC -#include -#include -#endif // _CRTDBG_MAP_ALLOC - -#include "VHACD.h" - - -using namespace VHACD; -using namespace std; - -bool replace(std::string& str, const std::string& from, const std::string& to) { - size_t start_pos = str.find(from); - if(start_pos == std::string::npos) - return false; - str.replace(start_pos, from.length(), to); - return true; -} - -class MyCallback : public IVHACD::IUserCallback { -public: - MyCallback(void) {} - ~MyCallback(){}; - void Update(const double overallProgress, const double stageProgress, const double operationProgress, - const char* const stage, const char* const operation) - { - cout << setfill(' ') << setw(3) << (int)(overallProgress + 0.5) << "% " - << "[ " << stage << " " << setfill(' ') << setw(3) << (int)(stageProgress + 0.5) << "% ] " - << operation << " " << setfill(' ') << setw(3) << (int)(operationProgress + 0.5) << "%" << endl; - }; -}; -class MyLogger : public IVHACD::IUserLogger { -public: - MyLogger(void) {} - MyLogger(const string& fileName) { OpenFile(fileName); } - ~MyLogger(){}; - void Log(const char* const msg) - { - if (m_file.is_open()) { - m_file << msg; - m_file.flush(); - } - } - void OpenFile(const string& fileName) - { - m_file.open(fileName.c_str()); - } - -private: - ofstream m_file; -}; -struct Material { - - float m_diffuseColor[3]; - float m_ambientIntensity; - float m_specularColor[3]; - float m_emissiveColor[3]; - float m_shininess; - float m_transparency; - Material(void) - { - m_diffuseColor[0] = 0.5f; - m_diffuseColor[1] = 0.5f; - m_diffuseColor[2] = 0.5f; - m_specularColor[0] = 0.5f; - m_specularColor[1] = 0.5f; - m_specularColor[2] = 0.5f; - m_ambientIntensity = 0.4f; - m_emissiveColor[0] = 0.0f; - m_emissiveColor[1] = 0.0f; - m_emissiveColor[2] = 0.0f; - m_shininess = 0.4f; - m_transparency = 0.5f; - }; -}; -struct Parameters { - unsigned int m_oclPlatformID; - unsigned int m_oclDeviceID; - string m_fileNameIn; - string m_fileNameOut; - string m_fileNameLog; - bool m_run; - IVHACD::Parameters m_paramsVHACD; - Parameters(void) - { - m_run = true; - m_oclPlatformID = 0; - m_oclDeviceID = 0; - m_fileNameIn = ""; - m_fileNameOut = "output.obj"; - m_fileNameLog = "log.txt"; - } -}; -bool LoadOFF(const string& fileName, vector& points, vector& triangles, IVHACD::IUserLogger& logger); -bool LoadOBJ(const string& fileName, vector& points, vector& triangles, IVHACD::IUserLogger& logger); -bool SaveOFF(const string& fileName, const float* const& points, const int* const& triangles, const unsigned int& nPoints, - const unsigned int& nTriangles, IVHACD::IUserLogger& logger); -bool SaveOBJ(ofstream& fout, const double* const& points, const int* const& triangles, const unsigned int& nPoints, - const unsigned int& nTriangles, const Material& material, IVHACD::IUserLogger& logger, int convexPart, int vertexOffset); - -bool SaveVRML2(ofstream& fout, const double* const& points, const int* const& triangles, const unsigned int& nPoints, - const unsigned int& nTriangles, const Material& material, IVHACD::IUserLogger& logger); -void GetFileExtension(const string& fileName, string& fileExtension); -void ComputeRandomColor(Material& mat); -void Usage(const Parameters& params); -void ParseParameters(int argc, char* argv[], Parameters& params); - - -int main(int argc, char* argv[]) -{ - // --input camel.off --output camel_acd.obj --log log.txt --resolution 1000000 --depth 20 --concavity 0.0025 --planeDownsampling 4 --convexhullDownsampling 4 --alpha 0.05 --beta 0.05 --gamma 0.00125 --pca 0 --mode 0 --maxNumVerticesPerCH 256 --minVolumePerCH 0.0001 --convexhullApproximation 1 --oclDeviceID 2 - { - // set parameters - Parameters params; - ParseParameters(argc, argv, params); - MyCallback myCallback; - MyLogger myLogger(params.m_fileNameLog); - params.m_paramsVHACD.m_logger = &myLogger; - params.m_paramsVHACD.m_callback = &myCallback; - Usage(params); - if (!params.m_run) { - return 0; - } - - std::ostringstream msg; - - msg << "+ OpenCL (OFF)" << std::endl; - - msg << "+ Parameters" << std::endl; - msg << "\t input " << params.m_fileNameIn << endl; - msg << "\t resolution " << params.m_paramsVHACD.m_resolution << endl; - msg << "\t max. depth " << params.m_paramsVHACD.m_depth << endl; - msg << "\t max. concavity " << params.m_paramsVHACD.m_concavity << endl; - msg << "\t plane down-sampling " << params.m_paramsVHACD.m_planeDownsampling << endl; - msg << "\t convex-hull down-sampling " << params.m_paramsVHACD.m_convexhullDownsampling << endl; - msg << "\t alpha " << params.m_paramsVHACD.m_alpha << endl; - msg << "\t beta " << params.m_paramsVHACD.m_beta << endl; - msg << "\t gamma " << params.m_paramsVHACD.m_gamma << endl; - msg << "\t pca " << params.m_paramsVHACD.m_pca << endl; - msg << "\t mode " << params.m_paramsVHACD.m_mode << endl; - msg << "\t max. vertices per convex-hull " << params.m_paramsVHACD.m_maxNumVerticesPerCH << endl; - msg << "\t min. volume to add vertices to convex-hulls " << params.m_paramsVHACD.m_minVolumePerCH << endl; - msg << "\t convex-hull approximation " << params.m_paramsVHACD.m_convexhullApproximation << endl; - msg << "\t OpenCL acceleration " << params.m_paramsVHACD.m_oclAcceleration << endl; - msg << "\t OpenCL platform ID " << params.m_oclPlatformID << endl; - msg << "\t OpenCL device ID " << params.m_oclDeviceID << endl; - msg << "\t output " << params.m_fileNameOut << endl; - msg << "\t log " << params.m_fileNameLog << endl; - msg << "+ Load mesh" << std::endl; - myLogger.Log(msg.str().c_str()); - - cout << msg.str().c_str(); - - // load mesh - vector points; - vector triangles; - string fileExtension; - GetFileExtension(params.m_fileNameIn, fileExtension); - if (fileExtension == ".OFF") { - if (!LoadOFF(params.m_fileNameIn, points, triangles, myLogger)) { - return -1; - } - } - else if (fileExtension == ".OBJ") { - if (!LoadOBJ(params.m_fileNameIn, points, triangles, myLogger)) { - return -1; - } - } - else { - myLogger.Log("Format not supported!\n"); - return -1; - } - - // run V-HACD - IVHACD* interfaceVHACD = CreateVHACD(); - -#ifdef CL_VERSION_1_1 - if (params.m_paramsVHACD.m_oclAcceleration) { - bool res = interfaceVHACD->OCLInit(oclHelper.GetDevice(), &myLogger); - if (!res) { - params.m_paramsVHACD.m_oclAcceleration = false; - } - } -#endif //CL_VERSION_1_1 - bool res = interfaceVHACD->Compute(&points[0], 3, (unsigned int)points.size() / 3, - &triangles[0], 3, (unsigned int)triangles.size() / 3, params.m_paramsVHACD); - if (res) { - // save output - unsigned int nConvexHulls = interfaceVHACD->GetNConvexHulls(); - msg.str(""); - msg << "+ Generate output: " << nConvexHulls << " convex-hulls " << endl; - myLogger.Log(msg.str().c_str()); - ofstream foutCH(params.m_fileNameOut.c_str()); - IVHACD::ConvexHull ch; - if (foutCH.is_open()) { - Material mat; - int vertexOffset = 1;//obj wavefront starts counting at 1... - for (unsigned int p = 0; p < nConvexHulls; ++p) { - interfaceVHACD->GetConvexHull(p, ch); - - - SaveOBJ(foutCH, ch.m_points, ch.m_triangles, ch.m_nPoints, ch.m_nTriangles, mat, myLogger, p, vertexOffset); - vertexOffset+=ch.m_nPoints; - msg.str(""); - msg << "\t CH[" << setfill('0') << setw(5) << p << "] " << ch.m_nPoints << " V, " << ch.m_nTriangles << " T" << endl; - myLogger.Log(msg.str().c_str()); - } - foutCH.close(); - } - } - else { - myLogger.Log("Decomposition cancelled by user!\n"); - } - -#ifdef CL_VERSION_1_1 - if (params.m_paramsVHACD.m_oclAcceleration) { - bool res = interfaceVHACD->OCLRelease(&myLogger); - if (!res) { - assert(-1); - } - } -#endif //CL_VERSION_1_1 - - interfaceVHACD->Clean(); - interfaceVHACD->Release(); - } -#ifdef _CRTDBG_MAP_ALLOC - _CrtDumpMemoryLeaks(); -#endif // _CRTDBG_MAP_ALLOC - return 0; -} - -void Usage(const Parameters& params) -{ - std::ostringstream msg; - msg << "V-HACD V" << VHACD_VERSION_MAJOR << "." << VHACD_VERSION_MINOR << endl; - msg << "Syntax: testVHACD [options] --input infile.obj --output outfile.obj --log logfile.txt" << endl - << endl; - msg << "Options:" << endl; - msg << " --input Wavefront .obj input file name" << endl; - msg << " --output VRML 2.0 output file name" << endl; - msg << " --log Log file name" << endl; - msg << " --resolution Maximum number of voxels generated during the voxelization stage (default=100,000, range=10,000-16,000,000)" << endl; - msg << " --depth Maximum number of clipping stages. During each split stage, parts with a concavity higher than the user defined threshold are clipped according the \"best\" clipping plane (default=20, range=1-32)" << endl; - msg << " --concavity Maximum allowed concavity (default=0.0025, range=0.0-1.0)" << endl; - msg << " --planeDownsampling Controls the granularity of the search for the \"best\" clipping plane (default=4, range=1-16)" << endl; - msg << " --convexhullDownsampling Controls the precision of the convex-hull generation process during the clipping plane selection stage (default=4, range=1-16)" << endl; - msg << " --alpha Controls the bias toward clipping along symmetry planes (default=0.05, range=0.0-1.0)" << endl; - msg << " --beta Controls the bias toward clipping along revolution axes (default=0.05, range=0.0-1.0)" << endl; - msg << " --gamma Controls the maximum allowed concavity during the merge stage (default=0.00125, range=0.0-1.0)" << endl; - msg << " --delta Controls the bias toward maximaxing local concavity (default=0.05, range=0.0-1.0)" << endl; - msg << " --pca Enable/disable normalizing the mesh before applying the convex decomposition (default=0, range={0,1})" << endl; - msg << " --mode 0: voxel-based approximate convex decomposition, 1: tetrahedron-based approximate convex decomposition (default=0, range={0,1})" << endl; - msg << " --maxNumVerticesPerCH Controls the maximum number of triangles per convex-hull (default=64, range=4-1024)" << endl; - msg << " --minVolumePerCH Controls the adaptive sampling of the generated convex-hulls (default=0.0001, range=0.0-0.01)" << endl; - msg << " --convexhullApproximation Enable/disable approximation when computing convex-hulls (default=1, range={0,1})" << endl; - msg << " --oclAcceleration Enable/disable OpenCL acceleration (default=0, range={0,1})" << endl; - msg << " --oclPlatformID OpenCL platform id (default=0, range=0-# OCL platforms)" << endl; - msg << " --oclDeviceID OpenCL device id (default=0, range=0-# OCL devices)" << endl; - msg << " --help Print usage" << endl - << endl; - msg << "Examples:" << endl; - msg << " testVHACD.exe --input bunny.obj --output bunny_acd.obj --log log.txt" << endl - << endl; - cout << msg.str(); - if (params.m_paramsVHACD.m_logger) { - params.m_paramsVHACD.m_logger->Log(msg.str().c_str()); - } -} -void ParseParameters(int argc, char* argv[], Parameters& params) -{ - for (int i = 1; i < argc; ++i) { - if (!strcmp(argv[i], "--input")) { - if (++i < argc) - { - params.m_fileNameIn = argv[i]; - //come up with some default output name, if not provided - if (params.m_fileNameOut.length()==0) - { - string tmp = argv[i]; - replace(tmp,".obj",".vhacd.obj"); - params.m_fileNameOut = tmp; - } - } - } - else if (!strcmp(argv[i], "--output")) { - if (++i < argc) - params.m_fileNameOut = argv[i]; - } - else if (!strcmp(argv[i], "--log")) { - if (++i < argc) - params.m_fileNameLog = argv[i]; - } - else if (!strcmp(argv[i], "--resolution")) { - if (++i < argc) - params.m_paramsVHACD.m_resolution = atoi(argv[i]); - } - else if (!strcmp(argv[i], "--depth")) { - if (++i < argc) - params.m_paramsVHACD.m_depth = atoi(argv[i]); - } - else if (!strcmp(argv[i], "--concavity")) { - if (++i < argc) - params.m_paramsVHACD.m_concavity = atof(argv[i]); - } - else if (!strcmp(argv[i], "--planeDownsampling")) { - if (++i < argc) - params.m_paramsVHACD.m_planeDownsampling = atoi(argv[i]); - } - else if (!strcmp(argv[i], "--convexhullDownsampling")) { - if (++i < argc) - params.m_paramsVHACD.m_convexhullDownsampling = atoi(argv[i]); - } - else if (!strcmp(argv[i], "--alpha")) { - if (++i < argc) - params.m_paramsVHACD.m_alpha = atof(argv[i]); - } - else if (!strcmp(argv[i], "--beta")) { - if (++i < argc) - params.m_paramsVHACD.m_beta = atof(argv[i]); - } - else if (!strcmp(argv[i], "--gamma")) { - if (++i < argc) - params.m_paramsVHACD.m_gamma = atof(argv[i]); - } - else if (!strcmp(argv[i], "--pca")) { - if (++i < argc) - params.m_paramsVHACD.m_pca = atoi(argv[i]); - } - else if (!strcmp(argv[i], "--mode")) { - if (++i < argc) - params.m_paramsVHACD.m_mode = atoi(argv[i]); - } - else if (!strcmp(argv[i], "--maxNumVerticesPerCH")) { - if (++i < argc) - params.m_paramsVHACD.m_maxNumVerticesPerCH = atoi(argv[i]); - } - else if (!strcmp(argv[i], "--minVolumePerCH")) { - if (++i < argc) - params.m_paramsVHACD.m_minVolumePerCH = atof(argv[i]); - } - else if (!strcmp(argv[i], "--convexhullApproximation")) { - if (++i < argc) - params.m_paramsVHACD.m_convexhullApproximation = atoi(argv[i]); - } - else if (!strcmp(argv[i], "--oclAcceleration")) { - if (++i < argc) - params.m_paramsVHACD.m_oclAcceleration = atoi(argv[i]); - } - else if (!strcmp(argv[i], "--oclPlatformID")) { - if (++i < argc) - params.m_oclPlatformID = atoi(argv[i]); - } - else if (!strcmp(argv[i], "--oclDeviceID")) { - if (++i < argc) - params.m_oclDeviceID = atoi(argv[i]); - } - else if (!strcmp(argv[i], "--help")) { - params.m_run = false; - } - } - params.m_paramsVHACD.m_resolution = (params.m_paramsVHACD.m_resolution < 64) ? 0 : params.m_paramsVHACD.m_resolution; - params.m_paramsVHACD.m_planeDownsampling = (params.m_paramsVHACD.m_planeDownsampling < 1) ? 1 : params.m_paramsVHACD.m_planeDownsampling; - params.m_paramsVHACD.m_convexhullDownsampling = (params.m_paramsVHACD.m_convexhullDownsampling < 1) ? 1 : params.m_paramsVHACD.m_convexhullDownsampling; -} - -void GetFileExtension(const string& fileName, string& fileExtension) -{ - size_t lastDotPosition = fileName.find_last_of("."); - if (lastDotPosition == string::npos) { - fileExtension = ""; - } - else { - fileExtension = fileName.substr(lastDotPosition, fileName.size()); - transform(fileExtension.begin(), fileExtension.end(), fileExtension.begin(), ::toupper); - } -} -void ComputeRandomColor(Material& mat) -{ - mat.m_diffuseColor[0] = mat.m_diffuseColor[1] = mat.m_diffuseColor[2] = 0.0f; - while (mat.m_diffuseColor[0] == mat.m_diffuseColor[1] || mat.m_diffuseColor[2] == mat.m_diffuseColor[1] || mat.m_diffuseColor[2] == mat.m_diffuseColor[0]) { - mat.m_diffuseColor[0] = (rand() % 100) / 100.0f; - mat.m_diffuseColor[1] = (rand() % 100) / 100.0f; - mat.m_diffuseColor[2] = (rand() % 100) / 100.0f; - } -} -bool LoadOFF(const string& fileName, vector& points, vector& triangles, IVHACD::IUserLogger& logger) -{ - FILE* fid = fopen(fileName.c_str(), "r"); - if (fid) { - const string strOFF("OFF"); - char temp[1024]; - fscanf(fid, "%s", temp); - if (string(temp) != strOFF) { - logger.Log("Loading error: format not recognized \n"); - fclose(fid); - return false; - } - else { - int nv = 0; - int nf = 0; - int ne = 0; - fscanf(fid, "%i", &nv); - fscanf(fid, "%i", &nf); - fscanf(fid, "%i", &ne); - points.resize(nv * 3); - triangles.resize(nf * 3); - const int np = nv * 3; - for (int p = 0; p < np; p++) { - fscanf(fid, "%f", &(points[p])); - } - int s; - for (int t = 0, r = 0; t < nf; ++t) { - fscanf(fid, "%i", &s); - if (s == 3) { - fscanf(fid, "%i", &(triangles[r++])); - fscanf(fid, "%i", &(triangles[r++])); - fscanf(fid, "%i", &(triangles[r++])); - } - else // Fix me: support only triangular meshes - { - for (int h = 0; h < s; ++h) - fscanf(fid, "%i", &s); - } - } - fclose(fid); - } - } - else { - logger.Log("Loading error: file not found \n"); - return false; - } - return true; -} -bool LoadOBJ(const string& fileName, vector& points, vector& triangles, IVHACD::IUserLogger& logger) -{ - const unsigned int BufferSize = 1024; - FILE* fid = fopen(fileName.c_str(), "r"); - - if (fid) { - char buffer[BufferSize]; - int ip[4]; - float x[3]; - char* pch; - char* str; - while (!feof(fid)) { - if (!fgets(buffer, BufferSize, fid)) { - break; - } - else if (buffer[0] == 'v') { - if (buffer[1] == ' ') { - str = buffer + 2; - for (int k = 0; k < 3; ++k) { - pch = strtok(str, " "); - if (pch) - x[k] = (float)atof(pch); - else { - return false; - } - str = NULL; - } - points.push_back(x[0]); - points.push_back(x[1]); - points.push_back(x[2]); - } - } - else if (buffer[0] == 'f') { - - pch = str = buffer + 2; - int k = 0; - while (pch) { - pch = strtok(str, " "); - if (pch) { - ip[k++] = atoi(pch) - 1; - } - else { - break; - } - str = NULL; - } - if (k == 3) { - triangles.push_back(ip[0]); - triangles.push_back(ip[1]); - triangles.push_back(ip[2]); - } - else if (k == 4) { - triangles.push_back(ip[0]); - triangles.push_back(ip[1]); - triangles.push_back(ip[2]); - - triangles.push_back(ip[0]); - triangles.push_back(ip[2]); - triangles.push_back(ip[3]); - } - } - } - fclose(fid); - } - else { - logger.Log("File not found\n"); - return false; - } - return true; -} -bool SaveOFF(const string& fileName, const float* const& points, const int* const& triangles, const unsigned int& nPoints, - const unsigned int& nTriangles, IVHACD::IUserLogger& logger) -{ - ofstream fout(fileName.c_str()); - if (fout.is_open()) { - size_t nV = nPoints * 3; - size_t nT = nTriangles * 3; - fout << "OFF" << std::endl; - fout << nPoints << " " << nTriangles << " " << 0 << std::endl; - for (size_t v = 0; v < nV; v += 3) { - fout << points[v + 0] << " " - << points[v + 1] << " " - << points[v + 2] << std::endl; - } - for (size_t f = 0; f < nT; f += 3) { - fout << "3 " << triangles[f + 0] << " " - << triangles[f + 1] << " " - << triangles[f + 2] << std::endl; - } - fout.close(); - return true; - } - else { - logger.Log("Can't open file\n"); - return false; - } -} - -bool SaveOBJ(ofstream& fout, const double* const& points, const int* const& triangles, const unsigned int& nPoints, - const unsigned int& nTriangles, const Material& material, IVHACD::IUserLogger& logger, int convexPart, int vertexOffset) -{ - if (fout.is_open()) { - - fout.setf(std::ios::fixed, std::ios::floatfield); - fout.setf(std::ios::showpoint); - fout.precision(6); - size_t nV = nPoints * 3; - size_t nT = nTriangles * 3; - - fout << "o convex_" << convexPart << std::endl; - - if (nV > 0) { - for (size_t v = 0; v < nV; v += 3) { - fout << "v " << points[v + 0] << " " << points[v + 1] << " " << points[v + 2] << std::endl; - } - } - if (nT > 0) { - for (size_t f = 0; f < nT; f += 3) { - fout << "f " - << triangles[f + 0]+vertexOffset << " " - << triangles[f + 1]+vertexOffset << " " - << triangles[f + 2]+vertexOffset << " " << std::endl; - } - } - return true; - } - else { - logger.Log("Can't open file\n"); - return false; - } -} - - - -bool SaveVRML2(ofstream& fout, const double* const& points, const int* const& triangles, const unsigned int& nPoints, - const unsigned int& nTriangles, const Material& material, IVHACD::IUserLogger& logger) -{ - if (fout.is_open()) { - fout.setf(std::ios::fixed, std::ios::floatfield); - fout.setf(std::ios::showpoint); - fout.precision(6); - size_t nV = nPoints * 3; - size_t nT = nTriangles * 3; - fout << "#VRML V2.0 utf8" << std::endl; - fout << "" << std::endl; - fout << "# Vertices: " << nPoints << std::endl; - fout << "# Triangles: " << nTriangles << std::endl; - fout << "" << std::endl; - fout << "Group {" << std::endl; - fout << " children [" << std::endl; - fout << " Shape {" << std::endl; - fout << " appearance Appearance {" << std::endl; - fout << " material Material {" << std::endl; - fout << " diffuseColor " << material.m_diffuseColor[0] << " " - << material.m_diffuseColor[1] << " " - << material.m_diffuseColor[2] << std::endl; - fout << " ambientIntensity " << material.m_ambientIntensity << std::endl; - fout << " specularColor " << material.m_specularColor[0] << " " - << material.m_specularColor[1] << " " - << material.m_specularColor[2] << std::endl; - fout << " emissiveColor " << material.m_emissiveColor[0] << " " - << material.m_emissiveColor[1] << " " - << material.m_emissiveColor[2] << std::endl; - fout << " shininess " << material.m_shininess << std::endl; - fout << " transparency " << material.m_transparency << std::endl; - fout << " }" << std::endl; - fout << " }" << std::endl; - fout << " geometry IndexedFaceSet {" << std::endl; - fout << " ccw TRUE" << std::endl; - fout << " solid TRUE" << std::endl; - fout << " convex TRUE" << std::endl; - if (nV > 0) { - fout << " coord DEF co Coordinate {" << std::endl; - fout << " point [" << std::endl; - for (size_t v = 0; v < nV; v += 3) { - fout << " " << points[v + 0] << " " - << points[v + 1] << " " - << points[v + 2] << "," << std::endl; - } - fout << " ]" << std::endl; - fout << " }" << std::endl; - } - if (nT > 0) { - fout << " coordIndex [ " << std::endl; - for (size_t f = 0; f < nT; f += 3) { - fout << " " << triangles[f + 0] << ", " - << triangles[f + 1] << ", " - << triangles[f + 2] << ", -1," << std::endl; - } - fout << " ]" << std::endl; - } - fout << " }" << std::endl; - fout << " }" << std::endl; - fout << " ]" << std::endl; - fout << "}" << std::endl; - return true; - } - else { - logger.Log("Can't open file\n"); - return false; - } -} diff --git a/extern/bullet/src/Extras/VHACD/test/src/oclHelper.cpp b/extern/bullet/src/Extras/VHACD/test/src/oclHelper.cpp deleted file mode 100644 index efaa9fa99e97..000000000000 --- a/extern/bullet/src/Extras/VHACD/test/src/oclHelper.cpp +++ /dev/null @@ -1,329 +0,0 @@ -/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com) -All rights reserved. - - -Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - -1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - -2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - -3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -*/ -#ifdef OPENCL_FOUND - -#include "oclHelper.h" -#include -#include - -bool OCLHelper::InitPlatform(const unsigned int platformIndex) -{ - cl_uint numPlatforms; - m_lastError = clGetPlatformIDs(1, NULL, &numPlatforms); - if (m_lastError != CL_SUCCESS || platformIndex >= numPlatforms) - return false; - - cl_platform_id* platforms = new cl_platform_id[numPlatforms]; - m_lastError = clGetPlatformIDs(numPlatforms, platforms, NULL); - if (m_lastError != CL_SUCCESS) { - delete[] platforms; - return false; - } - - m_platform = platforms[platformIndex]; - delete[] platforms; - return true; -} -bool OCLHelper::GetPlatformsInfo(std::vector& info, const std::string& indentation) -{ - const char* platformInfoParameters[] = { "CL_PLATFORM_NAME", - "CL_PLATFORM_VENDOR", - "CL_PLATFORM_VERSION", - "CL_PLATFORM_PROFILE", - "CL_PLATFORM_EXTENSIONS" }; - - cl_uint numPlatforms; - m_lastError = clGetPlatformIDs(1, NULL, &numPlatforms); - if (m_lastError != CL_SUCCESS) - return false; - - cl_platform_id* platforms = new cl_platform_id[numPlatforms]; - m_lastError = clGetPlatformIDs(numPlatforms, platforms, NULL); - if (m_lastError != CL_SUCCESS) { - delete[] platforms; - return false; - } - - size_t bufferSize = 4096; - char* buffer = new char[bufferSize]; - size_t size; - info.resize(numPlatforms); - for (cl_uint i = 0; i < numPlatforms; ++i) { - for (int j = CL_PLATFORM_PROFILE; j <= CL_PLATFORM_EXTENSIONS; ++j) { - info[i] += indentation + platformInfoParameters[j - CL_PLATFORM_PROFILE] + std::string(": "); - m_lastError = clGetPlatformInfo(platforms[i], j, 0, NULL, &size); - if (m_lastError != CL_SUCCESS) { - delete[] buffer; - delete[] platforms; - return false; - } - if (bufferSize < size) { - delete[] buffer; - bufferSize = size; - buffer = new char[bufferSize]; - } - m_lastError = clGetPlatformInfo(platforms[i], j, size, buffer, NULL); - if (m_lastError != CL_SUCCESS) { - delete[] buffer; - delete[] platforms; - return false; - } - info[i] += buffer + std::string("\n"); - } - } - delete[] platforms; - delete[] buffer; - return true; -} -bool OCLHelper::InitDevice(const unsigned int deviceIndex) -{ - cl_uint numDevices; - m_lastError = clGetDeviceIDs(m_platform, CL_DEVICE_TYPE_ALL, 0, NULL, &numDevices); - if (m_lastError != CL_SUCCESS || deviceIndex >= numDevices) - return false; - - cl_device_id* devices = new cl_device_id[numDevices]; - m_lastError = clGetDeviceIDs(m_platform, CL_DEVICE_TYPE_ALL, numDevices, devices, NULL); - if (m_lastError != CL_SUCCESS) { - delete[] devices; - return false; - } - m_device = devices[deviceIndex]; - delete[] devices; - return true; -} -bool OCLHelper::GetDevicesInfo(std::vector& info, const std::string& indentation) -{ - enum { - DATA_TYPE_CL_UINT, - DATA_TYPE_CL_BOOL, - DATA_TYPE_STRING, - DATA_TYPE_CL_ULONG, - DATA_TYPE_CL_DEVICE_FP_CONFIG, - DATA_TYPE_CL_DEVICE_EXEC_CAPABILITIES, - DATA_TYPE_CL_DEVICE_MEM_CACHE_TYPE, - DATA_TYPE_CL_DEVICE_MEM_LOCAL_TYPE, - DATA_TYPE_CL_DEVICE_CMD_QUEUE_PROP, - DATA_TYPE_CL_DEVICE_TYPE, - DATA_TYPE_SIZE_T, - DATA_TYPE_SIZE_T_3, - }; - typedef struct - { - cl_device_info id; - const char* name; - int type; - } DeviceInfoParam; - const int numDeviceInfoParameters = 49; - const DeviceInfoParam deviceInfoParameters[numDeviceInfoParameters] = { - { CL_DEVICE_NAME, "CL_DEVICE_NAME", DATA_TYPE_STRING }, - { CL_DEVICE_PROFILE, "CL_DEVICE_PROFILE", DATA_TYPE_STRING }, - { CL_DEVICE_VENDOR, "CL_DEVICE_VENDOR", DATA_TYPE_STRING }, - { CL_DEVICE_VERSION, "CL_DEVICE_VERSION", DATA_TYPE_STRING }, - { CL_DRIVER_VERSION, "CL_DRIVER_VERSION", DATA_TYPE_STRING }, - { CL_DEVICE_EXTENSIONS, "CL_DEVICE_EXTENSIONS", DATA_TYPE_STRING }, - { CL_DEVICE_VERSION, "CL_DEVICE_VERSION", DATA_TYPE_STRING }, - { CL_DEVICE_ADDRESS_BITS, "CL_DEVICE_ADDRESS_BITS", DATA_TYPE_CL_UINT }, - { CL_DEVICE_GLOBAL_MEM_CACHELINE_SIZE, "CL_DEVICE_GLOBAL_MEM_CACHELINE_SIZE", DATA_TYPE_CL_UINT }, - { CL_DEVICE_MAX_CLOCK_FREQUENCY, "CL_DEVICE_MAX_CLOCK_FREQUENCY", DATA_TYPE_CL_UINT }, - { CL_DEVICE_MAX_COMPUTE_UNITS, "CL_DEVICE_MAX_COMPUTE_UNITS", DATA_TYPE_CL_UINT }, - { CL_DEVICE_MAX_CONSTANT_ARGS, "CL_DEVICE_MAX_CONSTANT_ARGS", DATA_TYPE_CL_UINT }, - { CL_DEVICE_MAX_READ_IMAGE_ARGS, "CL_DEVICE_MAX_READ_IMAGE_ARGS", DATA_TYPE_CL_UINT }, - { CL_DEVICE_MAX_SAMPLERS, "CL_DEVICE_MAX_SAMPLERS", DATA_TYPE_CL_UINT }, - { CL_DEVICE_MAX_WORK_ITEM_DIMENSIONS, "CL_DEVICE_MAX_WORK_ITEM_DIMENSIONS", DATA_TYPE_CL_UINT }, - { CL_DEVICE_MAX_WRITE_IMAGE_ARGS, "CL_DEVICE_MAX_WRITE_IMAGE_ARGS", DATA_TYPE_CL_UINT }, - { CL_DEVICE_MEM_BASE_ADDR_ALIGN, "CL_DEVICE_MEM_BASE_ADDR_ALIGN", DATA_TYPE_CL_UINT }, - { CL_DEVICE_MIN_DATA_TYPE_ALIGN_SIZE, "CL_DEVICE_MIN_DATA_TYPE_ALIGN_SIZE", DATA_TYPE_CL_UINT }, - { CL_DEVICE_PREFERRED_VECTOR_WIDTH_CHAR, "CL_DEVICE_PREFERRED_VECTOR_WIDTH_CHAR", DATA_TYPE_CL_UINT }, - { CL_DEVICE_PREFERRED_VECTOR_WIDTH_SHORT, "CL_DEVICE_PREFERRED_VECTOR_WIDTH_SHORT", DATA_TYPE_CL_UINT }, - { CL_DEVICE_PREFERRED_VECTOR_WIDTH_INT, "CL_DEVICE_PREFERRED_VECTOR_WIDTH_INT", DATA_TYPE_CL_UINT }, - { CL_DEVICE_PREFERRED_VECTOR_WIDTH_LONG, "CL_DEVICE_PREFERRED_VECTOR_WIDTH_LONG", DATA_TYPE_CL_UINT }, - { CL_DEVICE_PREFERRED_VECTOR_WIDTH_FLOAT, "CL_DEVICE_PREFERRED_VECTOR_WIDTH_FLOAT", DATA_TYPE_CL_UINT }, - { CL_DEVICE_PREFERRED_VECTOR_WIDTH_DOUBLE, "CL_DEVICE_PREFERRED_VECTOR_WIDTH_DOUBLE", DATA_TYPE_CL_UINT }, - { CL_DEVICE_VENDOR_ID, "CL_DEVICE_VENDOR_ID", DATA_TYPE_CL_UINT }, - { CL_DEVICE_AVAILABLE, "CL_DEVICE_AVAILABLE", DATA_TYPE_CL_BOOL }, - { CL_DEVICE_COMPILER_AVAILABLE, "CL_DEVICE_COMPILER_AVAILABLE", DATA_TYPE_CL_BOOL }, - { CL_DEVICE_ENDIAN_LITTLE, "CL_DEVICE_ENDIAN_LITTLE", DATA_TYPE_CL_BOOL }, - { CL_DEVICE_ERROR_CORRECTION_SUPPORT, "CL_DEVICE_ERROR_CORRECTION_SUPPORT", DATA_TYPE_CL_BOOL }, - { CL_DEVICE_IMAGE_SUPPORT, "CL_DEVICE_IMAGE_SUPPORT", DATA_TYPE_CL_BOOL }, - { CL_DEVICE_EXECUTION_CAPABILITIES, "CL_DEVICE_EXECUTION_CAPABILITIES", DATA_TYPE_CL_DEVICE_EXEC_CAPABILITIES }, - { CL_DEVICE_GLOBAL_MEM_CACHE_SIZE, "CL_DEVICE_GLOBAL_MEM_CACHE_SIZE", DATA_TYPE_CL_ULONG }, - { CL_DEVICE_GLOBAL_MEM_SIZE, "CL_DEVICE_GLOBAL_MEM_SIZE", DATA_TYPE_CL_ULONG }, - { CL_DEVICE_LOCAL_MEM_SIZE, "CL_DEVICE_LOCAL_MEM_SIZE", DATA_TYPE_CL_ULONG }, - { CL_DEVICE_MAX_CONSTANT_BUFFER_SIZE, "CL_DEVICE_MAX_CONSTANT_BUFFER_SIZE", DATA_TYPE_CL_ULONG }, - { CL_DEVICE_MAX_MEM_ALLOC_SIZE, "CL_DEVICE_MAX_MEM_ALLOC_SIZE", DATA_TYPE_CL_ULONG }, - { CL_DEVICE_GLOBAL_MEM_CACHE_TYPE, "CL_DEVICE_GLOBAL_MEM_CACHE_TYPE", DATA_TYPE_CL_DEVICE_MEM_CACHE_TYPE }, - { CL_DEVICE_IMAGE2D_MAX_HEIGHT, "CL_DEVICE_IMAGE2D_MAX_HEIGHT", DATA_TYPE_SIZE_T }, - { CL_DEVICE_IMAGE2D_MAX_WIDTH, "CL_DEVICE_IMAGE2D_MAX_WIDTH", DATA_TYPE_SIZE_T }, - { CL_DEVICE_IMAGE3D_MAX_DEPTH, "CL_DEVICE_IMAGE3D_MAX_DEPTH", DATA_TYPE_SIZE_T }, - { CL_DEVICE_IMAGE3D_MAX_HEIGHT, "CL_DEVICE_IMAGE3D_MAX_HEIGHT", DATA_TYPE_SIZE_T }, - { CL_DEVICE_IMAGE3D_MAX_WIDTH, "CL_DEVICE_IMAGE3D_MAX_WIDTH", DATA_TYPE_SIZE_T }, - { CL_DEVICE_MAX_PARAMETER_SIZE, "CL_DEVICE_MAX_PARAMETER_SIZE", DATA_TYPE_SIZE_T }, - { CL_DEVICE_MAX_WORK_GROUP_SIZE, "CL_DEVICE_MAX_WORK_GROUP_SIZE", DATA_TYPE_SIZE_T }, - { CL_DEVICE_PROFILING_TIMER_RESOLUTION, "CL_DEVICE_PROFILING_TIMER_RESOLUTION", DATA_TYPE_SIZE_T }, - { CL_DEVICE_QUEUE_PROPERTIES, "CL_DEVICE_QUEUE_PROPERTIES", DATA_TYPE_CL_DEVICE_CMD_QUEUE_PROP }, - { CL_DEVICE_TYPE, "CL_DEVICE_TYPE", DATA_TYPE_CL_DEVICE_TYPE }, - { CL_DEVICE_LOCAL_MEM_TYPE, "CL_DEVICE_LOCAL_MEM_TYPE", DATA_TYPE_CL_DEVICE_MEM_LOCAL_TYPE }, - { CL_DEVICE_MAX_WORK_ITEM_SIZES, "CL_DEVICE_MAX_WORK_ITEM_SIZES", DATA_TYPE_SIZE_T_3 } - // { CL_DEVICE_DOUBLE_FP_CONFIG, "CL_DEVICE_DOUBLE_FP_CONFIG", DATA_TYPE_CL_DEVICE_FP_CONFIG }, - // - }; - cl_uint numDevices; - m_lastError = clGetDeviceIDs(m_platform, CL_DEVICE_TYPE_ALL, 0, NULL, &numDevices); - if (m_lastError != CL_SUCCESS) - return false; - - cl_device_id* devices = new cl_device_id[numDevices]; - m_lastError = clGetDeviceIDs(m_platform, CL_DEVICE_TYPE_ALL, numDevices, devices, NULL); - if (m_lastError != CL_SUCCESS) { - delete[] devices; - return false; - } - size_t bufferSize = 4096; - char* buffer = new char[bufferSize]; - size_t size; - info.resize(numDevices); - - for (cl_uint i = 0; i < numDevices; ++i) { - for (int j = 0; j < numDeviceInfoParameters; ++j) { - const DeviceInfoParam& infoParam = deviceInfoParameters[j]; - info[i] += indentation + infoParam.name + std::string(": "); - - if (infoParam.type == DATA_TYPE_STRING) { - m_lastError = clGetDeviceInfo(devices[i], infoParam.id, 0, NULL, &size); - if (m_lastError == CL_SUCCESS) { - if (bufferSize < size) { - delete[] buffer; - bufferSize = size; - buffer = new char[bufferSize]; - } - m_lastError = clGetDeviceInfo(devices[i], infoParam.id, size, buffer, NULL); - if (m_lastError != CL_SUCCESS) { - delete[] devices; - delete[] buffer; - return false; - } - info[i] += buffer + std::string("\n"); - } - } - else if (infoParam.type == DATA_TYPE_CL_UINT) { - cl_uint value; - m_lastError = clGetDeviceInfo(devices[i], infoParam.id, sizeof(cl_uint), &value, &size); - if (m_lastError == CL_SUCCESS) { - std::ostringstream svalue; - svalue << value; - info[i] += svalue.str() + "\n"; - } - } - else if (infoParam.type == DATA_TYPE_CL_BOOL) { - cl_bool value; - m_lastError = clGetDeviceInfo(devices[i], infoParam.id, sizeof(cl_bool), &value, &size); - if (m_lastError == CL_SUCCESS) { - std::ostringstream svalue; - svalue << value; - info[i] += svalue.str() + "\n"; - } - } - else if (infoParam.type == DATA_TYPE_CL_ULONG) { - cl_ulong value; - m_lastError = clGetDeviceInfo(devices[i], infoParam.id, sizeof(cl_ulong), &value, &size); - if (m_lastError == CL_SUCCESS) { - std::ostringstream svalue; - svalue << value; - info[i] += svalue.str() + "\n"; - } - } - else if (infoParam.type == DATA_TYPE_CL_DEVICE_FP_CONFIG) { - cl_device_fp_config value; - m_lastError = clGetDeviceInfo(devices[i], infoParam.id, sizeof(cl_device_fp_config), &value, &size); - if (m_lastError == CL_SUCCESS) { - std::ostringstream svalue; - svalue << value; - info[i] += svalue.str() + "\n"; - } - } - else if (infoParam.type == DATA_TYPE_CL_DEVICE_EXEC_CAPABILITIES) { - cl_device_exec_capabilities value; - m_lastError = clGetDeviceInfo(devices[i], infoParam.id, sizeof(cl_device_exec_capabilities), &value, &size); - if (m_lastError == CL_SUCCESS) { - std::ostringstream svalue; - svalue << value; - info[i] += svalue.str() + "\n"; - } - } - else if (infoParam.type == DATA_TYPE_CL_DEVICE_MEM_CACHE_TYPE) { - cl_device_mem_cache_type value; - m_lastError = clGetDeviceInfo(devices[i], infoParam.id, sizeof(cl_device_mem_cache_type), &value, &size); - if (m_lastError == CL_SUCCESS) { - std::ostringstream svalue; - svalue << value; - info[i] += svalue.str() + "\n"; - } - } - else if (infoParam.type == DATA_TYPE_CL_DEVICE_MEM_LOCAL_TYPE) { - cl_device_local_mem_type value; - m_lastError = clGetDeviceInfo(devices[i], infoParam.id, sizeof(cl_device_local_mem_type), &value, &size); - if (m_lastError == CL_SUCCESS) { - std::ostringstream svalue; - svalue << value; - info[i] += svalue.str() + "\n"; - } - } - else if (infoParam.type == DATA_TYPE_CL_DEVICE_CMD_QUEUE_PROP) { - cl_command_queue_properties value; - m_lastError = clGetDeviceInfo(devices[i], infoParam.id, sizeof(cl_command_queue_properties), &value, &size); - if (m_lastError == CL_SUCCESS) { - std::ostringstream svalue; - svalue << value; - info[i] += svalue.str() + "\n"; - } - } - else if (infoParam.type == DATA_TYPE_CL_DEVICE_TYPE) { - cl_device_type value; - m_lastError = clGetDeviceInfo(devices[i], infoParam.id, sizeof(cl_device_type), &value, &size); - if (m_lastError == CL_SUCCESS) { - std::ostringstream svalue; - svalue << value; - info[i] += svalue.str() + "\n"; - } - } - else if (infoParam.type == DATA_TYPE_SIZE_T) { - size_t value; - m_lastError = clGetDeviceInfo(devices[i], infoParam.id, sizeof(size_t), &value, &size); - if (m_lastError == CL_SUCCESS) { - std::ostringstream svalue; - svalue << value; - info[i] += svalue.str() + "\n"; - } - } - else if (infoParam.type == DATA_TYPE_SIZE_T_3) { - size_t value[3]; - m_lastError = clGetDeviceInfo(devices[i], infoParam.id, 3 * sizeof(size_t), &value, &size); - if (m_lastError == CL_SUCCESS) { - std::ostringstream svalue; - svalue << "(" << value[0] << ", " << value[1] << ", " << value[2] << ")"; - info[i] += svalue.str() + "\n"; - } - } - else { - assert(0); - } - } - } - delete[] devices; - delete[] buffer; - return true; -} -#endif // OPENCL_FOUND diff --git a/extern/bullet/src/Extras/VHACD/test/src/premake4.lua b/extern/bullet/src/Extras/VHACD/test/src/premake4.lua deleted file mode 100644 index a329f543950d..000000000000 --- a/extern/bullet/src/Extras/VHACD/test/src/premake4.lua +++ /dev/null @@ -1,25 +0,0 @@ - -project "test_vhacd" - -if _OPTIONS["ios"] then - kind "WindowedApp" -else - kind "ConsoleApp" -end - -includedirs {"../../public"} - -links { - "vhacd" -} - -language "C++" - -files { - "main.cpp", -} - - -if os.is("Linux") then - links {"pthread"} -end \ No newline at end of file diff --git a/extern/bullet/src/Extras/obj2sdf/CMakeLists.txt b/extern/bullet/src/Extras/obj2sdf/CMakeLists.txt deleted file mode 100644 index 6de9d51c6198..000000000000 --- a/extern/bullet/src/Extras/obj2sdf/CMakeLists.txt +++ /dev/null @@ -1,20 +0,0 @@ - -SET(includes - . - ${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs - ${BULLET_PHYSICS_SOURCE_DIR}/src -) - -LINK_LIBRARIES( - Bullet3Common -) - -INCLUDE_DIRECTORIES(${includes}) - -ADD_EXECUTABLE(App_obj2sdf - obj2sdf.cpp - ../../examples/Utils/b3ResourcePath.cpp - ../../examples/Utils/b3ResourcePath.h - ../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp -) - diff --git a/extern/bullet/src/Extras/obj2sdf/obj2sdf.cpp b/extern/bullet/src/Extras/obj2sdf/obj2sdf.cpp deleted file mode 100644 index 482e79211282..000000000000 --- a/extern/bullet/src/Extras/obj2sdf/obj2sdf.cpp +++ /dev/null @@ -1,452 +0,0 @@ -/// obj2sdf will load a Wavefront .obj file that may contain many parts/materials -/// it will split into separate obj files for each part/material and -/// create an sdf file with visuals/collisions pointing to the new obj files -/// this will make it easier to load complex obj files into pybullet -/// see for example export in data/kitchens/fathirmutfak.sdf - -#include -#include -#include -#define ASSERT_EQ(a,b) assert((a)==(b)); -#include"Wavefront/tiny_obj_loader.h" -#include -#include "Bullet3Common/b3FileUtils.h" -#include "../Utils/b3ResourcePath.h" -#include "Bullet3Common/b3CommandLineArgs.h" -#include "Bullet3Common/b3HashMap.h" - -struct ShapeContainer -{ - std::string m_matName; - std::string m_shapeName; - tinyobj::material_t material; - std::vector positions; - std::vector normals; - std::vector texcoords; - std::vector indices; - - b3AlignedObjectArray m_shapeIndices; -}; - -b3HashMap gMaterialNames; - -#define MAX_PATH_LEN 1024 - -std::string StripExtension( const std::string & sPath ) -{ - for( std::string::const_reverse_iterator i = sPath.rbegin(); i != sPath.rend(); i++ ) - { - if( *i == '.' ) - { - return std::string( sPath.begin(), i.base() - 1 ); - } - - // if we find a slash there is no extension - if( *i == '\\' || *i == '/' ) - break; - } - - // we didn't find an extension - return sPath; -} - -int main(int argc, char* argv[]) -{ - - b3CommandLineArgs args(argc,argv); - char* fileName; - args.GetCmdLineArgument("fileName",fileName); - if (fileName==0) - { - printf("required --fileName=\"name\""); - exit(0); - } - std::string matLibName = StripExtension(fileName); - - printf("fileName = %s\n", fileName); - if (fileName==0) - { - printf("Please use --fileName=\"pathToObj\"."); - exit(0); - } - bool mergeMaterials = args.CheckCmdLineFlag("mergeMaterials"); - - char fileNameWithPath[MAX_PATH_LEN]; - bool fileFound = (b3ResourcePath::findResourcePath(fileName,fileNameWithPath,MAX_PATH_LEN))>0; - char materialPrefixPath[MAX_PATH_LEN]; - b3FileUtils::extractPath(fileNameWithPath,materialPrefixPath,MAX_PATH_LEN); - - std::vector shapes; - std::string err = tinyobj::LoadObj(shapes, fileNameWithPath, materialPrefixPath); - - char sdfFileName[MAX_PATH_LEN]; - sprintf(sdfFileName,"%s%s.sdf",materialPrefixPath,"newsdf"); - FILE* sdfFile = fopen(sdfFileName,"w"); - if (sdfFile==0) - { - printf("Fatal error: cannot create sdf file %s\n",sdfFileName); - exit(0); - } - - fprintf(sdfFile, "\n\t\n\t0 0 -9.8\n"); - - for (int s = 0; s < (int)shapes.size(); s++) - { - tinyobj::shape_t& shape = shapes[s]; - tinyobj::material_t mat = shape.material; - - b3HashString key = mat.name.length() ? mat.name.c_str() : ""; - if (!gMaterialNames.find(key)) - { - ShapeContainer container; - container.m_matName = mat.name; - container.m_shapeName = shape.name; - container.material = mat; - gMaterialNames.insert(key, container); - } - - ShapeContainer* shapeC = gMaterialNames.find(key); - if (shapeC) - { - shapeC->m_shapeIndices.push_back(s); - - int curPositions = shapeC->positions.size()/3; - int curNormals = shapeC->normals.size()/3; - int curTexcoords = shapeC->texcoords.size()/2; - - int faceCount = shape.mesh.indices.size(); - int vertexCount = shape.mesh.positions.size(); - for (int v = 0; v < vertexCount; v++) - { - shapeC->positions.push_back(shape.mesh.positions[v]); - } - int numNormals = int(shape.mesh.normals.size()); - for (int vn = 0; vn < numNormals; vn++) - { - shapeC->normals.push_back(shape.mesh.normals[vn]); - } - int numTexCoords = int(shape.mesh.texcoords.size()); - for (int vt = 0; vt < numTexCoords; vt++) - { - shapeC->texcoords.push_back(shape.mesh.texcoords[vt]); - } - - for (int face = 0; face < faceCount; face += 3) - { - if (face < 0 && face >= int(shape.mesh.indices.size())) - { - continue; - } - - shapeC->indices.push_back(shape.mesh.indices[face] + curPositions); - shapeC->indices.push_back(shape.mesh.indices[face+1] + curPositions); - shapeC->indices.push_back(shape.mesh.indices[face + 2] + curPositions); - } - } - } - - printf("unique materials=%d\n", gMaterialNames.size()); - - - if (mergeMaterials) - { - for (int m = 0; m < gMaterialNames.size();m++) - { - if (gMaterialNames.getAtIndex(m)->m_shapeIndices.size() == 0) - continue; - - ShapeContainer* shapeCon =gMaterialNames.getAtIndex(m); - - printf("object name = %s\n", shapeCon->m_shapeName.c_str()); - - char objSdfPartFileName[MAX_PATH_LEN]; - sprintf(objSdfPartFileName, "part%d.obj", m); - - char objFileName[MAX_PATH_LEN]; - if (strlen(materialPrefixPath) > 0) - { - sprintf(objFileName, "%s/part%d.obj", materialPrefixPath, m); - } - else - { - sprintf(objFileName, "part%d.obj", m); - } - - - FILE* f = fopen(objFileName, "w"); - if (f == 0) - { - printf("Fatal error: cannot create part obj file %s\n", objFileName); - exit(0); - } - fprintf(f, "# Exported using automatic converter by Erwin Coumans\n"); - if (matLibName.length()) - { - fprintf(f, "mtllib %s.mtl\n", matLibName.c_str()); - } - else - { - fprintf(f, "mtllib bedroom.mtl\n"); - - } - - int faceCount = shapeCon->indices.size(); - int vertexCount = shapeCon->positions.size(); - tinyobj::material_t mat = shapeCon->material; - if (shapeCon->m_matName.length()) - { - const char* objName = shapeCon->m_matName.c_str(); - printf("mat.name = %s\n", objName); - fprintf(f, "#object %s\n\n", objName); - } - for (int v = 0; v < vertexCount / 3; v++) - { - fprintf(f, "v %f %f %f\n", shapeCon->positions[v * 3 + 0], shapeCon->positions[v * 3 + 1], shapeCon->positions[v * 3 + 2]); - } - - if (mat.name.length()) - { - fprintf(f, "usemtl %s\n", mat.name.c_str()); - } - else - { - fprintf(f, "usemtl wire_028089177\n"); - } - - fprintf(f, "\n"); - int numNormals = int(shapeCon->normals.size()); - - for (int vn = 0; vn < numNormals / 3; vn++) - { - fprintf(f, "vn %f %f %f\n", shapeCon->normals[vn * 3 + 0], shapeCon->normals[vn * 3 + 1], shapeCon->normals[vn * 3 + 2]); - } - - fprintf(f, "\n"); - int numTexCoords = int(shapeCon->texcoords.size()); - for (int vt = 0; vt < numTexCoords / 2; vt++) - { - fprintf(f, "vt %f %f\n", shapeCon->texcoords[vt * 2 + 0], shapeCon->texcoords[vt * 2 + 1]); - } - - fprintf(f, "s off\n"); - - for (int face = 0; face < faceCount; face += 3) - { - if (face < 0 && face >= int(shapeCon->indices.size())) - { - continue; - } - fprintf(f, "f %d/%d/%d %d/%d/%d %d/%d/%d\n", - shapeCon->indices[face] + 1, shapeCon->indices[face] + 1, shapeCon->indices[face] + 1, - shapeCon->indices[face + 1] + 1, shapeCon->indices[face + 1] + 1, shapeCon->indices[face + 1] + 1, - shapeCon->indices[face + 2] + 1, shapeCon->indices[face + 2] + 1, shapeCon->indices[face + 2] + 1); - } - fclose(f); - - float kdRed = mat.diffuse[0]; - float kdGreen = mat.diffuse[1]; - float kdBlue = mat.diffuse[2]; - float transparency = mat.transparency; - - fprintf(sdfFile, "\t\t\n" - "\t\t\t1\n" - "\t\t\t0 0 0 0 0 0\n" - "\t\t\t\n" - "\t\t\t\n" - "\t\t\t0\n" - "\t\t\t\n" - "\t\t\t0.166667\n" - "\t\t\t0\n" - "\t\t\t0\n" - "\t\t\t0.166667\n" - "\t\t\t0\n" - "\t\t\t0.166667\n" - "\t\t\t\n" - "\t\t\t\n" - "\t\t\t\n" - "\t\t\t\n" - "\t\t\t\n" - "\t\t\t1 1 1\n" - "\t\t\t\t%s\n" - "\t\t\t\n" - "\t\t\t\n" - "\t\t\t \n" - "\t\t\t\n" - "\t\t\t\t\n" - "\t\t\t\t\n" - "\t\t\t\t\t1 1 1\n" - "\t\t\t\t\t%s\n" - "\t\t\t\t\n" - "\t\t\t\t\n" - "\t\t\t\n" - "\t\t\t\t1 0 0 1\n" - "\t\t\t\t%f %f %f %f\n" - "\t\t\t\t0.1 0.1 0.1 1\n" - "\t\t\t\t0 0 0 0\n" - "\t\t\t \n" - "\t\t\t \n" - "\t\t\t \n" - "\t\t\t\n", objSdfPartFileName, m, m, - objSdfPartFileName, objSdfPartFileName, - kdRed, kdGreen, kdBlue, transparency); - - - } - - - - - - - - - } - else - { - - for (int s = 0; s < (int)shapes.size(); s++) - { - tinyobj::shape_t& shape = shapes[s]; - - if (shape.name.length()) - { - printf("object name = %s\n", shape.name.c_str()); - } - - char objFileName[MAX_PATH_LEN]; - if (strlen(materialPrefixPath) > 0) - { - sprintf(objFileName, "%s/part%d.obj", materialPrefixPath, s); - } - else - { - sprintf(objFileName, "part%d.obj", s); - } - FILE* f = fopen(objFileName, "w"); - if (f == 0) - { - printf("Fatal error: cannot create part obj file %s\n", objFileName); - exit(0); - } - fprintf(f, "# Exported using automatic converter by Erwin Coumans\n"); - if (matLibName.length()) - { - fprintf(f, "mtllib %s.mtl\n", matLibName.c_str()); - } - else - { - fprintf(f, "mtllib bedroom.mtl\n"); - - } - - - int faceCount = shape.mesh.indices.size(); - int vertexCount = shape.mesh.positions.size(); - tinyobj::material_t mat = shape.material; - if (shape.name.length()) - { - const char* objName = shape.name.c_str(); - printf("mat.name = %s\n", objName); - fprintf(f, "#object %s\n\n", objName); - } - for (int v = 0; v < vertexCount / 3; v++) - { - fprintf(f, "v %f %f %f\n", shape.mesh.positions[v * 3 + 0], shape.mesh.positions[v * 3 + 1], shape.mesh.positions[v * 3 + 2]); - } - - if (mat.name.length()) - { - fprintf(f, "usemtl %s\n", mat.name.c_str()); - } - else - { - fprintf(f, "usemtl wire_028089177\n"); - } - - fprintf(f, "\n"); - int numNormals = int(shape.mesh.normals.size()); - - for (int vn = 0; vn < numNormals / 3; vn++) - { - fprintf(f, "vn %f %f %f\n", shape.mesh.normals[vn * 3 + 0], shape.mesh.normals[vn * 3 + 1], shape.mesh.normals[vn * 3 + 2]); - } - - fprintf(f, "\n"); - int numTexCoords = int(shape.mesh.texcoords.size()); - for (int vt = 0; vt < numTexCoords / 2; vt++) - { - fprintf(f, "vt %f %f\n", shape.mesh.texcoords[vt * 2 + 0], shape.mesh.texcoords[vt * 2 + 1]); - } - - fprintf(f, "s off\n"); - - for (int face = 0; face < faceCount; face += 3) - { - if (face < 0 && face >= int(shape.mesh.indices.size())) - { - continue; - } - fprintf(f, "f %d/%d/%d %d/%d/%d %d/%d/%d\n", - shape.mesh.indices[face] + 1, shape.mesh.indices[face] + 1, shape.mesh.indices[face] + 1, - shape.mesh.indices[face + 1] + 1, shape.mesh.indices[face + 1] + 1, shape.mesh.indices[face + 1] + 1, - shape.mesh.indices[face + 2] + 1, shape.mesh.indices[face + 2] + 1, shape.mesh.indices[face + 2] + 1); - } - fclose(f); - - float kdRed = mat.diffuse[0]; - float kdGreen = mat.diffuse[1]; - float kdBlue = mat.diffuse[2]; - float transparency = mat.transparency; - char objSdfPartFileName[MAX_PATH_LEN]; - sprintf(objSdfPartFileName, "part%d.obj", s); - fprintf(sdfFile, "\t\t\n" - "\t\t\t1\n" - "\t\t\t0 0 0 0 0 0\n" - "\t\t\t\n" - "\t\t\t\n" - "\t\t\t0\n" - "\t\t\t\n" - "\t\t\t0.166667\n" - "\t\t\t0\n" - "\t\t\t0\n" - "\t\t\t0.166667\n" - "\t\t\t0\n" - "\t\t\t0.166667\n" - "\t\t\t\n" - "\t\t\t\n" - "\t\t\t\n" - "\t\t\t\n" - "\t\t\t\n" - "\t\t\t1 1 1\n" - "\t\t\t\t%s\n" - "\t\t\t\n" - "\t\t\t\n" - "\t\t\t \n" - "\t\t\t\n" - "\t\t\t\t\n" - "\t\t\t\t\n" - "\t\t\t\t\t1 1 1\n" - "\t\t\t\t\t%s\n" - "\t\t\t\t\n" - "\t\t\t\t\n" - "\t\t\t\n" - "\t\t\t\t1 0 0 1\n" - "\t\t\t\t%f %f %f %f\n" - "\t\t\t\t0.1 0.1 0.1 1\n" - "\t\t\t\t0 0 0 0\n" - "\t\t\t \n" - "\t\t\t \n" - "\t\t\t \n" - "\t\t\t\n", objSdfPartFileName, s, s, - objSdfPartFileName, objSdfPartFileName, - kdRed, kdGreen, kdBlue, transparency); - - - } - } - fprintf(sdfFile,"\t\n\n"); - - fclose(sdfFile); - - return 0; -} diff --git a/extern/bullet/src/Extras/obj2sdf/premake4.lua b/extern/bullet/src/Extras/obj2sdf/premake4.lua deleted file mode 100644 index 07f0190928b1..000000000000 --- a/extern/bullet/src/Extras/obj2sdf/premake4.lua +++ /dev/null @@ -1,18 +0,0 @@ -project ("App_obj2sdf") - - language "C++" - kind "ConsoleApp" - - includedirs {"../../src", - "../../examples/ThirdPartyLibs"} - - - links{"Bullet3Common"} - - - files { - "obj2sdf.cpp", - "../../examples/Utils/b3ResourcePath.cpp", - "../../examples/Utils/b3ResourcePath.h", - "../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp", - } diff --git a/extern/bullet/src/Extras/premake4.lua b/extern/bullet/src/Extras/premake4.lua deleted file mode 100644 index 416c019d4132..000000000000 --- a/extern/bullet/src/Extras/premake4.lua +++ /dev/null @@ -1,10 +0,0 @@ - -include "HACD" -include "VHACD" -include "ConvexDecomposition" -include "InverseDynamics" -include "Serialize/BulletFileLoader" -include "Serialize/BulletWorldImporter" -include "Serialize/BulletXmlWorldImporter" -include "obj2sdf" -include "BulletRobotics" diff --git a/extern/bullet/src/LinearMath/CMakeLists.txt b/extern/bullet/src/LinearMath/CMakeLists.txt index 0c8c0133a325..ede21d9a70c9 100644 --- a/extern/bullet/src/LinearMath/CMakeLists.txt +++ b/extern/bullet/src/LinearMath/CMakeLists.txt @@ -14,9 +14,6 @@ SET(LinearMath_SRCS btSerializer64.cpp btThreads.cpp btVector3.cpp - TaskScheduler/btTaskScheduler.cpp - TaskScheduler/btThreadSupportPosix.cpp - TaskScheduler/btThreadSupportWin32.cpp ) SET(LinearMath_HDRS @@ -47,7 +44,6 @@ SET(LinearMath_HDRS btTransform.h btTransformUtil.h btVector3.h - TaskScheduler/btThreadSupportInterface.h ) ADD_LIBRARY(LinearMath ${LinearMath_SRCS} ${LinearMath_HDRS}) diff --git a/extern/bullet/src/LinearMath/TaskScheduler/btTaskScheduler.cpp b/extern/bullet/src/LinearMath/TaskScheduler/btTaskScheduler.cpp deleted file mode 100644 index 49510d16601b..000000000000 --- a/extern/bullet/src/LinearMath/TaskScheduler/btTaskScheduler.cpp +++ /dev/null @@ -1,802 +0,0 @@ - -#include "LinearMath/btMinMax.h" -#include "LinearMath/btAlignedObjectArray.h" -#include "LinearMath/btThreads.h" -#include "LinearMath/btQuickprof.h" -#include -#include - - - -#if BT_THREADSAFE - -#include "btThreadSupportInterface.h" - -#if defined( _WIN32 ) - -#define WIN32_LEAN_AND_MEAN - -#include - -#endif - - -typedef unsigned long long btU64; -static const int kCacheLineSize = 64; - -void btSpinPause() -{ -#if defined( _WIN32 ) - YieldProcessor(); -#endif -} - - -struct WorkerThreadStatus -{ - enum Type - { - kInvalid, - kWaitingForWork, - kWorking, - kSleeping, - }; -}; - - -ATTRIBUTE_ALIGNED64(class) WorkerThreadDirectives -{ - static const int kMaxThreadCount = BT_MAX_THREAD_COUNT; - // directives for all worker threads packed into a single cacheline - char m_threadDirs[kMaxThreadCount]; - -public: - enum Type - { - kInvalid, - kGoToSleep, // go to sleep - kStayAwakeButIdle, // wait for not checking job queue - kScanForJobs, // actively scan job queue for jobs - }; - WorkerThreadDirectives() - { - for ( int i = 0; i < kMaxThreadCount; ++i ) - { - m_threadDirs[ i ] = 0; - } - } - - Type getDirective(int threadId) - { - btAssert(threadId < kMaxThreadCount); - return static_cast(m_threadDirs[threadId]); - } - - void setDirectiveByRange(int threadBegin, int threadEnd, Type dir) - { - btAssert( threadBegin < threadEnd ); - btAssert( threadEnd <= kMaxThreadCount ); - char dirChar = static_cast(dir); - for ( int i = threadBegin; i < threadEnd; ++i ) - { - m_threadDirs[ i ] = dirChar; - } - } -}; - -class JobQueue; - -ATTRIBUTE_ALIGNED64(struct) ThreadLocalStorage -{ - int m_threadId; - WorkerThreadStatus::Type m_status; - int m_numJobsFinished; - btSpinMutex m_mutex; - btScalar m_sumResult; - WorkerThreadDirectives * m_directive; - JobQueue* m_queue; - btClock* m_clock; - unsigned int m_cooldownTime; -}; - - -struct IJob -{ - virtual void executeJob(int threadId) = 0; -}; - -class ParallelForJob : public IJob -{ - const btIParallelForBody* m_body; - int m_begin; - int m_end; - -public: - ParallelForJob( int iBegin, int iEnd, const btIParallelForBody& body ) - { - m_body = &body; - m_begin = iBegin; - m_end = iEnd; - } - virtual void executeJob(int threadId) BT_OVERRIDE - { - BT_PROFILE( "executeJob" ); - - // call the functor body to do the work - m_body->forLoop( m_begin, m_end ); - } -}; - - -class ParallelSumJob : public IJob -{ - const btIParallelSumBody* m_body; - ThreadLocalStorage* m_threadLocalStoreArray; - int m_begin; - int m_end; - -public: - ParallelSumJob( int iBegin, int iEnd, const btIParallelSumBody& body, ThreadLocalStorage* tls ) - { - m_body = &body; - m_threadLocalStoreArray = tls; - m_begin = iBegin; - m_end = iEnd; - } - virtual void executeJob( int threadId ) BT_OVERRIDE - { - BT_PROFILE( "executeJob" ); - - // call the functor body to do the work - btScalar val = m_body->sumLoop( m_begin, m_end ); -#if BT_PARALLEL_SUM_DETERMINISTISM - // by truncating bits of the result, we can make the parallelSum deterministic (at the expense of precision) - const float TRUNC_SCALE = float(1<<19); - val = floor(val*TRUNC_SCALE+0.5f)/TRUNC_SCALE; // truncate some bits -#endif - m_threadLocalStoreArray[threadId].m_sumResult += val; - } -}; - - -ATTRIBUTE_ALIGNED64(class) JobQueue -{ - btThreadSupportInterface* m_threadSupport; - btCriticalSection* m_queueLock; - btSpinMutex m_mutex; - - btAlignedObjectArray m_jobQueue; - char* m_jobMem; - int m_jobMemSize; - bool m_queueIsEmpty; - int m_tailIndex; - int m_headIndex; - int m_allocSize; - bool m_useSpinMutex; - btAlignedObjectArray m_neighborContexts; - char m_cachePadding[kCacheLineSize]; // prevent false sharing - - void freeJobMem() - { - if ( m_jobMem ) - { - // free old - btAlignedFree(m_jobMem); - m_jobMem = NULL; - } - } - void resizeJobMem(int newSize) - { - if (newSize > m_jobMemSize) - { - freeJobMem(); - m_jobMem = static_cast(btAlignedAlloc(newSize, kCacheLineSize)); - m_jobMemSize = newSize; - } - } - -public: - - JobQueue() - { - m_jobMem = NULL; - m_jobMemSize = 0; - m_threadSupport = NULL; - m_queueLock = NULL; - m_headIndex = 0; - m_tailIndex = 0; - m_useSpinMutex = false; - } - ~JobQueue() - { - exit(); - } - void exit() - { - freeJobMem(); - if (m_queueLock && m_threadSupport) - { - m_threadSupport->deleteCriticalSection(m_queueLock); - m_queueLock = NULL; - m_threadSupport = 0; - } - } - - void init(btThreadSupportInterface* threadSup, btAlignedObjectArray* contextArray) - { - m_threadSupport = threadSup; - if (threadSup) - { - m_queueLock = m_threadSupport->createCriticalSection(); - } - setupJobStealing(contextArray, contextArray->size()); - } - void setupJobStealing(btAlignedObjectArray* contextArray, int numActiveContexts) - { - btAlignedObjectArray& contexts = *contextArray; - int selfIndex = 0; - for (int i = 0; i < contexts.size(); ++i) - { - if ( this == &contexts[ i ] ) - { - selfIndex = i; - break; - } - } - int numNeighbors = btMin(2, contexts.size() - 1); - int neighborOffsets[ ] = {-1, 1, -2, 2, -3, 3}; - int numOffsets = sizeof(neighborOffsets)/sizeof(neighborOffsets[0]); - m_neighborContexts.reserve( numNeighbors ); - m_neighborContexts.resizeNoInitialize(0); - for (int i = 0; i < numOffsets && m_neighborContexts.size() < numNeighbors; i++) - { - int neighborIndex = selfIndex + neighborOffsets[i]; - if ( neighborIndex >= 0 && neighborIndex < numActiveContexts) - { - m_neighborContexts.push_back( &contexts[ neighborIndex ] ); - } - } - } - - bool isQueueEmpty() const {return m_queueIsEmpty;} - void lockQueue() - { - if ( m_useSpinMutex ) - { - m_mutex.lock(); - } - else - { - m_queueLock->lock(); - } - } - void unlockQueue() - { - if ( m_useSpinMutex ) - { - m_mutex.unlock(); - } - else - { - m_queueLock->unlock(); - } - } - void clearQueue(int jobCount, int jobSize) - { - lockQueue(); - m_headIndex = 0; - m_tailIndex = 0; - m_allocSize = 0; - m_queueIsEmpty = true; - int jobBufSize = jobSize * jobCount; - // make sure we have enough memory allocated to store jobs - if ( jobBufSize > m_jobMemSize ) - { - resizeJobMem( jobBufSize ); - } - // make sure job queue is big enough - if ( jobCount > m_jobQueue.capacity() ) - { - m_jobQueue.reserve( jobCount ); - } - unlockQueue(); - m_jobQueue.resizeNoInitialize( 0 ); - } - void* allocJobMem(int jobSize) - { - btAssert(m_jobMemSize >= (m_allocSize + jobSize)); - void* jobMem = &m_jobMem[m_allocSize]; - m_allocSize += jobSize; - return jobMem; - } - void submitJob( IJob* job ) - { - btAssert( reinterpret_cast( job ) >= &m_jobMem[ 0 ] && reinterpret_cast( job ) < &m_jobMem[ 0 ] + m_allocSize ); - m_jobQueue.push_back( job ); - lockQueue(); - m_tailIndex++; - m_queueIsEmpty = false; - unlockQueue(); - } - IJob* consumeJobFromOwnQueue() - { - if ( m_queueIsEmpty ) - { - // lock free path. even if this is taken erroneously it isn't harmful - return NULL; - } - IJob* job = NULL; - lockQueue(); - if ( !m_queueIsEmpty ) - { - job = m_jobQueue[ m_headIndex++ ]; - btAssert( reinterpret_cast( job ) >= &m_jobMem[ 0 ] && reinterpret_cast( job ) < &m_jobMem[ 0 ] + m_allocSize ); - if ( m_headIndex == m_tailIndex ) - { - m_queueIsEmpty = true; - } - } - unlockQueue(); - return job; - } - IJob* consumeJob() - { - if (IJob* job = consumeJobFromOwnQueue()) - { - return job; - } - // own queue is empty, try to steal from neighbor - for (int i = 0; i < m_neighborContexts.size(); ++i) - { - JobQueue* otherContext = m_neighborContexts[ i ]; - if ( IJob* job = otherContext->consumeJobFromOwnQueue() ) - { - return job; - } - } - return NULL; - } -}; - - -static void WorkerThreadFunc( void* userPtr ) -{ - BT_PROFILE( "WorkerThreadFunc" ); - ThreadLocalStorage* localStorage = (ThreadLocalStorage*) userPtr; - JobQueue* jobQueue = localStorage->m_queue; - - bool shouldSleep = false; - int threadId = localStorage->m_threadId; - while (! shouldSleep) - { - // do work - localStorage->m_mutex.lock(); - while ( IJob* job = jobQueue->consumeJob() ) - { - localStorage->m_status = WorkerThreadStatus::kWorking; - job->executeJob( threadId ); - localStorage->m_numJobsFinished++; - } - localStorage->m_status = WorkerThreadStatus::kWaitingForWork; - localStorage->m_mutex.unlock(); - btU64 clockStart = localStorage->m_clock->getTimeMicroseconds(); - // while queue is empty, - while (jobQueue->isQueueEmpty()) - { - // todo: spin wait a bit to avoid hammering the empty queue - btSpinPause(); - if ( localStorage->m_directive->getDirective(threadId) == WorkerThreadDirectives::kGoToSleep ) - { - shouldSleep = true; - break; - } - // if jobs are incoming, - if ( localStorage->m_directive->getDirective( threadId ) == WorkerThreadDirectives::kScanForJobs ) - { - clockStart = localStorage->m_clock->getTimeMicroseconds(); // reset clock - } - else - { - for ( int i = 0; i < 50; ++i ) - { - btSpinPause(); - btSpinPause(); - btSpinPause(); - btSpinPause(); - if (localStorage->m_directive->getDirective( threadId ) == WorkerThreadDirectives::kScanForJobs || !jobQueue->isQueueEmpty()) - { - break; - } - } - // if no jobs incoming and queue has been empty for the cooldown time, sleep - btU64 timeElapsed = localStorage->m_clock->getTimeMicroseconds() - clockStart; - if (timeElapsed > localStorage->m_cooldownTime) - { - shouldSleep = true; - break; - } - } - } - } - { - BT_PROFILE("sleep"); - // go sleep - localStorage->m_mutex.lock(); - localStorage->m_status = WorkerThreadStatus::kSleeping; - localStorage->m_mutex.unlock(); - } -} - - -class btTaskSchedulerDefault : public btITaskScheduler -{ - btThreadSupportInterface* m_threadSupport; - WorkerThreadDirectives* m_workerDirective; - btAlignedObjectArray m_jobQueues; - btAlignedObjectArray m_perThreadJobQueues; - btAlignedObjectArray m_threadLocalStorage; - btSpinMutex m_antiNestingLock; // prevent nested parallel-for - btClock m_clock; - int m_numThreads; - int m_numWorkerThreads; - int m_numActiveJobQueues; - int m_maxNumThreads; - int m_numJobs; - static const int kFirstWorkerThreadId = 1; -public: - - btTaskSchedulerDefault() : btITaskScheduler("ThreadSupport") - { - m_threadSupport = NULL; - m_workerDirective = NULL; - } - - virtual ~btTaskSchedulerDefault() - { - waitForWorkersToSleep(); - - for ( int i = 0; i < m_jobQueues.size(); ++i ) - { - m_jobQueues[i].exit(); - } - - if (m_threadSupport) - { - delete m_threadSupport; - m_threadSupport = NULL; - } - if (m_workerDirective) - { - btAlignedFree(m_workerDirective); - m_workerDirective = NULL; - } - } - - void init() - { - btThreadSupportInterface::ConstructionInfo constructionInfo( "TaskScheduler", WorkerThreadFunc ); - m_threadSupport = btThreadSupportInterface::create( constructionInfo ); - m_workerDirective = static_cast(btAlignedAlloc(sizeof(*m_workerDirective), 64)); - - m_numWorkerThreads = m_threadSupport->getNumWorkerThreads(); - m_maxNumThreads = m_threadSupport->getNumWorkerThreads() + 1; - m_numThreads = m_maxNumThreads; - // ideal to have one job queue for each physical processor (except for the main thread which needs no queue) - int numThreadsPerQueue = m_threadSupport->getLogicalToPhysicalCoreRatio(); - int numJobQueues = (numThreadsPerQueue == 1) ? (m_maxNumThreads-1) : (m_maxNumThreads / numThreadsPerQueue); - m_jobQueues.resize(numJobQueues); - m_numActiveJobQueues = numJobQueues; - for ( int i = 0; i < m_jobQueues.size(); ++i ) - { - m_jobQueues[i].init( m_threadSupport, &m_jobQueues ); - } - m_perThreadJobQueues.resize(m_numThreads); - for ( int i = 0; i < m_numThreads; i++ ) - { - JobQueue* jq = NULL; - // only worker threads get a job queue - if (i > 0) - { - if (numThreadsPerQueue == 1) - { - // one queue per worker thread - jq = &m_jobQueues[ i - kFirstWorkerThreadId ]; - } - else - { - // 2 threads share each queue - jq = &m_jobQueues[ i / numThreadsPerQueue ]; - } - } - m_perThreadJobQueues[i] = jq; - } - m_threadLocalStorage.resize(m_numThreads); - for ( int i = 0; i < m_numThreads; i++ ) - { - ThreadLocalStorage& storage = m_threadLocalStorage[i]; - storage.m_threadId = i; - storage.m_directive = m_workerDirective; - storage.m_status = WorkerThreadStatus::kSleeping; - storage.m_cooldownTime = 100; // 100 microseconds, threads go to sleep after this long if they have nothing to do - storage.m_clock = &m_clock; - storage.m_queue = m_perThreadJobQueues[i]; - } - setWorkerDirectives( WorkerThreadDirectives::kGoToSleep ); // no work for them yet - setNumThreads( m_threadSupport->getCacheFriendlyNumThreads() ); - } - - void setWorkerDirectives(WorkerThreadDirectives::Type dir) - { - m_workerDirective->setDirectiveByRange(kFirstWorkerThreadId, m_numThreads, dir); - } - - virtual int getMaxNumThreads() const BT_OVERRIDE - { - return m_maxNumThreads; - } - - virtual int getNumThreads() const BT_OVERRIDE - { - return m_numThreads; - } - - virtual void setNumThreads( int numThreads ) BT_OVERRIDE - { - m_numThreads = btMax( btMin(numThreads, int(m_maxNumThreads)), 1 ); - m_numWorkerThreads = m_numThreads - 1; - m_numActiveJobQueues = 0; - // if there is at least 1 worker, - if ( m_numWorkerThreads > 0 ) - { - // re-setup job stealing between queues to avoid attempting to steal from an inactive job queue - JobQueue* lastActiveContext = m_perThreadJobQueues[ m_numThreads - 1 ]; - int iLastActiveContext = lastActiveContext - &m_jobQueues[0]; - m_numActiveJobQueues = iLastActiveContext + 1; - for ( int i = 0; i < m_jobQueues.size(); ++i ) - { - m_jobQueues[ i ].setupJobStealing( &m_jobQueues, m_numActiveJobQueues ); - } - } - m_workerDirective->setDirectiveByRange(m_numThreads, BT_MAX_THREAD_COUNT, WorkerThreadDirectives::kGoToSleep); - } - - void waitJobs() - { - BT_PROFILE( "waitJobs" ); - // have the main thread work until the job queues are empty - int numMainThreadJobsFinished = 0; - for ( int i = 0; i < m_numActiveJobQueues; ++i ) - { - while ( IJob* job = m_jobQueues[i].consumeJob() ) - { - job->executeJob( 0 ); - numMainThreadJobsFinished++; - } - } - - // done with jobs for now, tell workers to rest (but not sleep) - setWorkerDirectives( WorkerThreadDirectives::kStayAwakeButIdle ); - - btU64 clockStart = m_clock.getTimeMicroseconds(); - // wait for workers to finish any jobs in progress - while ( true ) - { - int numWorkerJobsFinished = 0; - for ( int iThread = kFirstWorkerThreadId; iThread < m_numThreads; ++iThread ) - { - ThreadLocalStorage* storage = &m_threadLocalStorage[iThread]; - storage->m_mutex.lock(); - numWorkerJobsFinished += storage->m_numJobsFinished; - storage->m_mutex.unlock(); - } - if (numWorkerJobsFinished + numMainThreadJobsFinished == m_numJobs) - { - break; - } - btU64 timeElapsed = m_clock.getTimeMicroseconds() - clockStart; - btAssert(timeElapsed < 1000); - if (timeElapsed > 100000) - { - break; - } - btSpinPause(); - } - } - - void wakeWorkers(int numWorkersToWake) - { - BT_PROFILE( "wakeWorkers" ); - btAssert( m_workerDirective->getDirective(1) == WorkerThreadDirectives::kScanForJobs ); - int numDesiredWorkers = btMin(numWorkersToWake, m_numWorkerThreads); - int numActiveWorkers = 0; - for ( int iWorker = 0; iWorker < m_numWorkerThreads; ++iWorker ) - { - // note this count of active workers is not necessarily totally reliable, because a worker thread could be - // just about to put itself to sleep. So we may on occasion fail to wake up all the workers. It should be rare. - ThreadLocalStorage& storage = m_threadLocalStorage[ kFirstWorkerThreadId + iWorker ]; - if (storage.m_status != WorkerThreadStatus::kSleeping) - { - numActiveWorkers++; - } - } - for ( int iWorker = 0; iWorker < m_numWorkerThreads && numActiveWorkers < numDesiredWorkers; ++iWorker ) - { - ThreadLocalStorage& storage = m_threadLocalStorage[ kFirstWorkerThreadId + iWorker ]; - if (storage.m_status == WorkerThreadStatus::kSleeping) - { - m_threadSupport->runTask( iWorker, &storage ); - numActiveWorkers++; - } - } - } - - void waitForWorkersToSleep() - { - BT_PROFILE( "waitForWorkersToSleep" ); - setWorkerDirectives( WorkerThreadDirectives::kGoToSleep ); - m_threadSupport->waitForAllTasks(); - for ( int i = kFirstWorkerThreadId; i < m_numThreads; i++ ) - { - ThreadLocalStorage& storage = m_threadLocalStorage[i]; - btAssert( storage.m_status == WorkerThreadStatus::kSleeping ); - } - } - - virtual void sleepWorkerThreadsHint() BT_OVERRIDE - { - BT_PROFILE( "sleepWorkerThreadsHint" ); - // hint the task scheduler that we may not be using these threads for a little while - setWorkerDirectives( WorkerThreadDirectives::kGoToSleep ); - } - - void prepareWorkerThreads() - { - for ( int i = kFirstWorkerThreadId; i < m_numThreads; ++i ) - { - ThreadLocalStorage& storage = m_threadLocalStorage[i]; - storage.m_mutex.lock(); - storage.m_numJobsFinished = 0; - storage.m_mutex.unlock(); - } - setWorkerDirectives( WorkerThreadDirectives::kScanForJobs ); - } - - virtual void parallelFor( int iBegin, int iEnd, int grainSize, const btIParallelForBody& body ) BT_OVERRIDE - { - BT_PROFILE( "parallelFor_ThreadSupport" ); - btAssert( iEnd >= iBegin ); - btAssert( grainSize >= 1 ); - int iterationCount = iEnd - iBegin; - if ( iterationCount > grainSize && m_numWorkerThreads > 0 && m_antiNestingLock.tryLock() ) - { - typedef ParallelForJob JobType; - int jobCount = ( iterationCount + grainSize - 1 ) / grainSize; - m_numJobs = jobCount; - btAssert( jobCount >= 2 ); // need more than one job for multithreading - int jobSize = sizeof( JobType ); - - for (int i = 0; i < m_numActiveJobQueues; ++i) - { - m_jobQueues[i].clearQueue( jobCount, jobSize ); - } - // prepare worker threads for incoming work - prepareWorkerThreads(); - // submit all of the jobs - int iJob = 0; - int iThread = kFirstWorkerThreadId; // first worker thread - for ( int i = iBegin; i < iEnd; i += grainSize ) - { - btAssert( iJob < jobCount ); - int iE = btMin( i + grainSize, iEnd ); - JobQueue* jq = m_perThreadJobQueues[ iThread ]; - btAssert(jq); - btAssert((jq - &m_jobQueues[0]) < m_numActiveJobQueues); - void* jobMem = jq->allocJobMem(jobSize); - JobType* job = new ( jobMem ) ParallelForJob( i, iE, body ); // placement new - jq->submitJob( job ); - iJob++; - iThread++; - if ( iThread >= m_numThreads ) - { - iThread = kFirstWorkerThreadId; // first worker thread - } - } - wakeWorkers( jobCount - 1 ); - - // put the main thread to work on emptying the job queue and then wait for all workers to finish - waitJobs(); - m_antiNestingLock.unlock(); - } - else - { - BT_PROFILE( "parallelFor_mainThread" ); - // just run on main thread - body.forLoop( iBegin, iEnd ); - } - } - virtual btScalar parallelSum( int iBegin, int iEnd, int grainSize, const btIParallelSumBody& body ) BT_OVERRIDE - { - BT_PROFILE( "parallelSum_ThreadSupport" ); - btAssert( iEnd >= iBegin ); - btAssert( grainSize >= 1 ); - int iterationCount = iEnd - iBegin; - if ( iterationCount > grainSize && m_numWorkerThreads > 0 && m_antiNestingLock.tryLock() ) - { - typedef ParallelSumJob JobType; - int jobCount = ( iterationCount + grainSize - 1 ) / grainSize; - m_numJobs = jobCount; - btAssert( jobCount >= 2 ); // need more than one job for multithreading - int jobSize = sizeof( JobType ); - for (int i = 0; i < m_numActiveJobQueues; ++i) - { - m_jobQueues[i].clearQueue( jobCount, jobSize ); - } - - // initialize summation - for ( int iThread = 0; iThread < m_numThreads; ++iThread ) - { - m_threadLocalStorage[iThread].m_sumResult = btScalar(0); - } - - // prepare worker threads for incoming work - prepareWorkerThreads(); - // submit all of the jobs - int iJob = 0; - int iThread = kFirstWorkerThreadId; // first worker thread - for ( int i = iBegin; i < iEnd; i += grainSize ) - { - btAssert( iJob < jobCount ); - int iE = btMin( i + grainSize, iEnd ); - JobQueue* jq = m_perThreadJobQueues[ iThread ]; - btAssert(jq); - btAssert((jq - &m_jobQueues[0]) < m_numActiveJobQueues); - void* jobMem = jq->allocJobMem(jobSize); - JobType* job = new ( jobMem ) ParallelSumJob( i, iE, body, &m_threadLocalStorage[0] ); // placement new - jq->submitJob( job ); - iJob++; - iThread++; - if ( iThread >= m_numThreads ) - { - iThread = kFirstWorkerThreadId; // first worker thread - } - } - wakeWorkers( jobCount - 1 ); - - // put the main thread to work on emptying the job queue and then wait for all workers to finish - waitJobs(); - - // add up all the thread sums - btScalar sum = btScalar(0); - for ( int iThread = 0; iThread < m_numThreads; ++iThread ) - { - sum += m_threadLocalStorage[ iThread ].m_sumResult; - } - m_antiNestingLock.unlock(); - return sum; - } - else - { - BT_PROFILE( "parallelSum_mainThread" ); - // just run on main thread - return body.sumLoop( iBegin, iEnd ); - } - } -}; - - - -btITaskScheduler* btCreateDefaultTaskScheduler() -{ - btTaskSchedulerDefault* ts = new btTaskSchedulerDefault(); - ts->init(); - return ts; -} - -#else // #if BT_THREADSAFE - -btITaskScheduler* btCreateDefaultTaskScheduler() -{ - return NULL; -} - -#endif // #else // #if BT_THREADSAFE diff --git a/extern/bullet/src/LinearMath/TaskScheduler/btThreadSupportInterface.h b/extern/bullet/src/LinearMath/TaskScheduler/btThreadSupportInterface.h deleted file mode 100644 index a0ad802b1e12..000000000000 --- a/extern/bullet/src/LinearMath/TaskScheduler/btThreadSupportInterface.h +++ /dev/null @@ -1,70 +0,0 @@ -/* -Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2018 Erwin Coumans http://bulletphysics.com - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#ifndef BT_THREAD_SUPPORT_INTERFACE_H -#define BT_THREAD_SUPPORT_INTERFACE_H - - - -class btCriticalSection -{ -public: - btCriticalSection() {} - virtual ~btCriticalSection() {} - - virtual void lock() = 0; - virtual void unlock() = 0; -}; - - -class btThreadSupportInterface -{ -public: - - virtual ~btThreadSupportInterface() {} - - virtual int getNumWorkerThreads() const = 0; // number of worker threads (total number of logical processors - 1) - virtual int getCacheFriendlyNumThreads() const = 0; // the number of logical processors sharing a single L3 cache - virtual int getLogicalToPhysicalCoreRatio() const = 0; // the number of logical processors per physical processor (usually 1 or 2) - virtual void runTask( int threadIndex, void* userData ) = 0; - virtual void waitForAllTasks() = 0; - - virtual btCriticalSection* createCriticalSection() = 0; - virtual void deleteCriticalSection( btCriticalSection* criticalSection ) = 0; - - typedef void( *ThreadFunc )( void* userPtr ); - - struct ConstructionInfo - { - ConstructionInfo( const char* uniqueName, - ThreadFunc userThreadFunc, - int threadStackSize = 65535 - ) - :m_uniqueName( uniqueName ), - m_userThreadFunc( userThreadFunc ), - m_threadStackSize( threadStackSize ) - { - } - - const char* m_uniqueName; - ThreadFunc m_userThreadFunc; - int m_threadStackSize; - }; - - static btThreadSupportInterface* create( const ConstructionInfo& info ); -}; - -#endif //BT_THREAD_SUPPORT_INTERFACE_H - diff --git a/extern/bullet/src/LinearMath/TaskScheduler/btThreadSupportPosix.cpp b/extern/bullet/src/LinearMath/TaskScheduler/btThreadSupportPosix.cpp deleted file mode 100644 index 50ca060dfec7..000000000000 --- a/extern/bullet/src/LinearMath/TaskScheduler/btThreadSupportPosix.cpp +++ /dev/null @@ -1,365 +0,0 @@ -/* -Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2018 Erwin Coumans http://bulletphysics.com - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - - -#if BT_THREADSAFE && !defined( _WIN32 ) - - -#include "LinearMath/btScalar.h" -#include "LinearMath/btAlignedObjectArray.h" -#include "LinearMath/btThreads.h" -#include "LinearMath/btMinMax.h" -#include "btThreadSupportInterface.h" - -#include -#include -#include - - -#ifndef _XOPEN_SOURCE -#define _XOPEN_SOURCE 600 //for definition of pthread_barrier_t, see http://pages.cs.wisc.edu/~travitch/pthreads_primer.html -#endif //_XOPEN_SOURCE -#include -#include -#include //for sysconf - - -/// -/// getNumHardwareThreads() -/// -/// -/// https://stackoverflow.com/questions/150355/programmatically-find-the-number-of-cores-on-a-machine -/// -#if __cplusplus >= 201103L - -#include - -int btGetNumHardwareThreads() -{ - return btMin(BT_MAX_THREAD_COUNT, std::thread::hardware_concurrency()); -} - -#else - -int btGetNumHardwareThreads() -{ - return btMin(BT_MAX_THREAD_COUNT, sysconf( _SC_NPROCESSORS_ONLN )); -} - -#endif - - -// btThreadSupportPosix helps to initialize/shutdown libspe2, start/stop SPU tasks and communication -class btThreadSupportPosix : public btThreadSupportInterface -{ -public: - struct btThreadStatus - { - int m_taskId; - int m_commandId; - int m_status; - - ThreadFunc m_userThreadFunc; - void* m_userPtr; //for taskDesc etc - - pthread_t thread; - //each tread will wait until this signal to start its work - sem_t* startSemaphore; - - // this is a copy of m_mainSemaphore, - //each tread will signal once it is finished with its work - sem_t* m_mainSemaphore; - unsigned long threadUsed; - }; -private: - typedef unsigned long long UINT64; - - btAlignedObjectArray m_activeThreadStatus; - // m_mainSemaphoresemaphore will signal, if and how many threads are finished with their work - sem_t* m_mainSemaphore; - int m_numThreads; - UINT64 m_startedThreadsMask; - void startThreads( const ConstructionInfo& threadInfo ); - void stopThreads(); - int waitForResponse(); - -public: - btThreadSupportPosix( const ConstructionInfo& threadConstructionInfo ); - virtual ~btThreadSupportPosix(); - - virtual int getNumWorkerThreads() const BT_OVERRIDE { return m_numThreads; } - // TODO: return the number of logical processors sharing the first L3 cache - virtual int getCacheFriendlyNumThreads() const BT_OVERRIDE { return m_numThreads + 1; } - // TODO: detect if CPU has hyperthreading enabled - virtual int getLogicalToPhysicalCoreRatio() const BT_OVERRIDE { return 1; } - - virtual void runTask( int threadIndex, void* userData ) BT_OVERRIDE; - virtual void waitForAllTasks() BT_OVERRIDE; - - virtual btCriticalSection* createCriticalSection() BT_OVERRIDE; - virtual void deleteCriticalSection( btCriticalSection* criticalSection ) BT_OVERRIDE; -}; - - -#define checkPThreadFunction(returnValue) \ - if(0 != returnValue) { \ - printf("PThread problem at line %i in file %s: %i %d\n", __LINE__, __FILE__, returnValue, errno); \ - } - -// The number of threads should be equal to the number of available cores -// Todo: each worker should be linked to a single core, using SetThreadIdealProcessor. - - -btThreadSupportPosix::btThreadSupportPosix( const ConstructionInfo& threadConstructionInfo ) -{ - startThreads( threadConstructionInfo ); -} - -// cleanup/shutdown Libspe2 -btThreadSupportPosix::~btThreadSupportPosix() -{ - stopThreads(); -} - -#if (defined (__APPLE__)) -#define NAMED_SEMAPHORES -#endif - - -static sem_t* createSem( const char* baseName ) -{ - static int semCount = 0; -#ifdef NAMED_SEMAPHORES - /// Named semaphore begin - char name[ 32 ]; - snprintf( name, 32, "/%8.s-%4.d-%4.4d", baseName, getpid(), semCount++ ); - sem_t* tempSem = sem_open( name, O_CREAT, 0600, 0 ); - - if ( tempSem != reinterpret_cast( SEM_FAILED ) ) - { - // printf("Created \"%s\" Semaphore %p\n", name, tempSem); - } - else - { - //printf("Error creating Semaphore %d\n", errno); - exit( -1 ); - } - /// Named semaphore end -#else - sem_t* tempSem = new sem_t; - checkPThreadFunction( sem_init( tempSem, 0, 0 ) ); -#endif - return tempSem; -} - -static void destroySem( sem_t* semaphore ) -{ -#ifdef NAMED_SEMAPHORES - checkPThreadFunction( sem_close( semaphore ) ); -#else - checkPThreadFunction( sem_destroy( semaphore ) ); - delete semaphore; -#endif -} - -static void *threadFunction( void *argument ) -{ - btThreadSupportPosix::btThreadStatus* status = ( btThreadSupportPosix::btThreadStatus* )argument; - - while ( 1 ) - { - checkPThreadFunction( sem_wait( status->startSemaphore ) ); - void* userPtr = status->m_userPtr; - - if ( userPtr ) - { - btAssert( status->m_status ); - status->m_userThreadFunc( userPtr ); - status->m_status = 2; - checkPThreadFunction( sem_post( status->m_mainSemaphore ) ); - status->threadUsed++; - } - else - { - //exit Thread - status->m_status = 3; - checkPThreadFunction( sem_post( status->m_mainSemaphore ) ); - printf( "Thread with taskId %i exiting\n", status->m_taskId ); - break; - } - } - - printf( "Thread TERMINATED\n" ); - return 0; -} - -///send messages to SPUs -void btThreadSupportPosix::runTask( int threadIndex, void* userData ) -{ - ///we should spawn an SPU task here, and in 'waitForResponse' it should wait for response of the (one of) the first tasks that finished - btThreadStatus& threadStatus = m_activeThreadStatus[ threadIndex ]; - btAssert( threadIndex >= 0 ); - btAssert( threadIndex < m_activeThreadStatus.size() ); - - threadStatus.m_commandId = 1; - threadStatus.m_status = 1; - threadStatus.m_userPtr = userData; - m_startedThreadsMask |= UINT64( 1 ) << threadIndex; - - // fire event to start new task - checkPThreadFunction( sem_post( threadStatus.startSemaphore ) ); -} - - -///check for messages from SPUs -int btThreadSupportPosix::waitForResponse() -{ - ///We should wait for (one of) the first tasks to finish (or other SPU messages), and report its response - ///A possible response can be 'yes, SPU handled it', or 'no, please do a PPU fallback' - - btAssert( m_activeThreadStatus.size() ); - - // wait for any of the threads to finish - checkPThreadFunction( sem_wait( m_mainSemaphore ) ); - // get at least one thread which has finished - size_t last = -1; - - for ( size_t t = 0; t < size_t( m_activeThreadStatus.size() ); ++t ) - { - if ( 2 == m_activeThreadStatus[ t ].m_status ) - { - last = t; - break; - } - } - - btThreadStatus& threadStatus = m_activeThreadStatus[ last ]; - - btAssert( threadStatus.m_status > 1 ); - threadStatus.m_status = 0; - - // need to find an active spu - btAssert( last >= 0 ); - m_startedThreadsMask &= ~( UINT64( 1 ) << last ); - - return last; -} - - -void btThreadSupportPosix::waitForAllTasks() -{ - while ( m_startedThreadsMask ) - { - waitForResponse(); - } -} - - -void btThreadSupportPosix::startThreads( const ConstructionInfo& threadConstructionInfo ) -{ - m_numThreads = btGetNumHardwareThreads() - 1; // main thread exists already - printf( "%s creating %i threads.\n", __FUNCTION__, m_numThreads ); - m_activeThreadStatus.resize( m_numThreads ); - m_startedThreadsMask = 0; - - m_mainSemaphore = createSem( "main" ); - //checkPThreadFunction(sem_wait(mainSemaphore)); - - for ( int i = 0; i < m_numThreads; i++ ) - { - printf( "starting thread %d\n", i ); - btThreadStatus& threadStatus = m_activeThreadStatus[ i ]; - threadStatus.startSemaphore = createSem( "threadLocal" ); - checkPThreadFunction( pthread_create( &threadStatus.thread, NULL, &threadFunction, (void*) &threadStatus ) ); - - threadStatus.m_userPtr = 0; - threadStatus.m_taskId = i; - threadStatus.m_commandId = 0; - threadStatus.m_status = 0; - threadStatus.m_mainSemaphore = m_mainSemaphore; - threadStatus.m_userThreadFunc = threadConstructionInfo.m_userThreadFunc; - threadStatus.threadUsed = 0; - - printf( "started thread %d \n", i ); - } -} - -///tell the task scheduler we are done with the SPU tasks -void btThreadSupportPosix::stopThreads() -{ - for ( size_t t = 0; t < size_t( m_activeThreadStatus.size() ); ++t ) - { - btThreadStatus& threadStatus = m_activeThreadStatus[ t ]; - printf( "%s: Thread %i used: %ld\n", __FUNCTION__, int( t ), threadStatus.threadUsed ); - - threadStatus.m_userPtr = 0; - checkPThreadFunction( sem_post( threadStatus.startSemaphore ) ); - checkPThreadFunction( sem_wait( m_mainSemaphore ) ); - - printf( "destroy semaphore\n" ); - destroySem( threadStatus.startSemaphore ); - printf( "semaphore destroyed\n" ); - checkPThreadFunction( pthread_join( threadStatus.thread, 0 ) ); - - } - printf( "destroy main semaphore\n" ); - destroySem( m_mainSemaphore ); - printf( "main semaphore destroyed\n" ); - m_activeThreadStatus.clear(); -} - -class btCriticalSectionPosix : public btCriticalSection -{ - pthread_mutex_t m_mutex; - -public: - btCriticalSectionPosix() - { - pthread_mutex_init( &m_mutex, NULL ); - } - virtual ~btCriticalSectionPosix() - { - pthread_mutex_destroy( &m_mutex ); - } - - virtual void lock() - { - pthread_mutex_lock( &m_mutex ); - } - virtual void unlock() - { - pthread_mutex_unlock( &m_mutex ); - } -}; - - -btCriticalSection* btThreadSupportPosix::createCriticalSection() -{ - return new btCriticalSectionPosix(); -} - -void btThreadSupportPosix::deleteCriticalSection( btCriticalSection* cs ) -{ - delete cs; -} - - -btThreadSupportInterface* btThreadSupportInterface::create( const ConstructionInfo& info ) -{ - return new btThreadSupportPosix( info ); -} - -#endif // BT_THREADSAFE && !defined( _WIN32 ) - diff --git a/extern/bullet/src/LinearMath/TaskScheduler/btThreadSupportWin32.cpp b/extern/bullet/src/LinearMath/TaskScheduler/btThreadSupportWin32.cpp deleted file mode 100644 index 00edac650b43..000000000000 --- a/extern/bullet/src/LinearMath/TaskScheduler/btThreadSupportWin32.cpp +++ /dev/null @@ -1,472 +0,0 @@ -/* -Bullet Continuous Collision Detection and Physics Library -Copyright (c) 2003-2018 Erwin Coumans http://bulletphysics.com - -This software is provided 'as-is', without any express or implied warranty. -In no event will the authors be held liable for any damages arising from the use of this software. -Permission is granted to anyone to use this software for any purpose, -including commercial applications, and to alter it and redistribute it freely, -subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. -2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. -3. This notice may not be removed or altered from any source distribution. -*/ - -#if defined( _WIN32 ) && BT_THREADSAFE - -#include "LinearMath/btScalar.h" -#include "LinearMath/btMinMax.h" -#include "LinearMath/btAlignedObjectArray.h" -#include "LinearMath/btThreads.h" -#include "btThreadSupportInterface.h" -#include -#include - - -struct btProcessorInfo -{ - int numLogicalProcessors; - int numCores; - int numNumaNodes; - int numL1Cache; - int numL2Cache; - int numL3Cache; - int numPhysicalPackages; - static const int maxNumTeamMasks = 32; - int numTeamMasks; - UINT64 processorTeamMasks[ maxNumTeamMasks ]; -}; - -UINT64 getProcessorTeamMask( const btProcessorInfo& procInfo, int procId ) -{ - UINT64 procMask = UINT64( 1 ) << procId; - for ( int i = 0; i < procInfo.numTeamMasks; ++i ) - { - if ( procMask & procInfo.processorTeamMasks[ i ] ) - { - return procInfo.processorTeamMasks[ i ]; - } - } - return 0; -} - -int getProcessorTeamIndex( const btProcessorInfo& procInfo, int procId ) -{ - UINT64 procMask = UINT64( 1 ) << procId; - for ( int i = 0; i < procInfo.numTeamMasks; ++i ) - { - if ( procMask & procInfo.processorTeamMasks[ i ] ) - { - return i; - } - } - return -1; -} - -int countSetBits( ULONG64 bits ) -{ - int count = 0; - while ( bits ) - { - if ( bits & 1 ) - { - count++; - } - bits >>= 1; - } - return count; -} - - -typedef BOOL( WINAPI *Pfn_GetLogicalProcessorInformation )( PSYSTEM_LOGICAL_PROCESSOR_INFORMATION, PDWORD ); - - -void getProcessorInformation( btProcessorInfo* procInfo ) -{ - memset( procInfo, 0, sizeof( *procInfo ) ); - Pfn_GetLogicalProcessorInformation getLogicalProcInfo = - (Pfn_GetLogicalProcessorInformation) GetProcAddress( GetModuleHandle( TEXT( "kernel32" ) ), "GetLogicalProcessorInformation" ); - if ( getLogicalProcInfo == NULL ) - { - // no info - return; - } - PSYSTEM_LOGICAL_PROCESSOR_INFORMATION buf = NULL; - DWORD bufSize = 0; - while ( true ) - { - if ( getLogicalProcInfo( buf, &bufSize ) ) - { - break; - } - else - { - if ( GetLastError() == ERROR_INSUFFICIENT_BUFFER ) - { - if ( buf ) - { - free( buf ); - } - buf = (PSYSTEM_LOGICAL_PROCESSOR_INFORMATION) malloc( bufSize ); - } - } - } - - int len = bufSize / sizeof( *buf ); - for ( int i = 0; i < len; ++i ) - { - PSYSTEM_LOGICAL_PROCESSOR_INFORMATION info = buf + i; - switch ( info->Relationship ) - { - case RelationNumaNode: - procInfo->numNumaNodes++; - break; - - case RelationProcessorCore: - procInfo->numCores++; - procInfo->numLogicalProcessors += countSetBits( info->ProcessorMask ); - break; - - case RelationCache: - if ( info->Cache.Level == 1 ) - { - procInfo->numL1Cache++; - } - else if ( info->Cache.Level == 2 ) - { - procInfo->numL2Cache++; - } - else if ( info->Cache.Level == 3 ) - { - procInfo->numL3Cache++; - // processors that share L3 cache are considered to be on the same team - // because they can more easily work together on the same data. - // Large performance penalties will occur if 2 or more threads from different - // teams attempt to frequently read and modify the same cache lines. - // - // On the AMD Ryzen 7 CPU for example, the 8 cores on the CPU are split into - // 2 CCX units of 4 cores each. Each CCX has a separate L3 cache, so if both - // CCXs are operating on the same data, many cycles will be spent keeping the - // two caches coherent. - if ( procInfo->numTeamMasks < btProcessorInfo::maxNumTeamMasks ) - { - procInfo->processorTeamMasks[ procInfo->numTeamMasks ] = info->ProcessorMask; - procInfo->numTeamMasks++; - } - } - break; - - case RelationProcessorPackage: - procInfo->numPhysicalPackages++; - break; - } - } - free( buf ); -} - - - -///btThreadSupportWin32 helps to initialize/shutdown libspe2, start/stop SPU tasks and communication -class btThreadSupportWin32 : public btThreadSupportInterface -{ -public: - struct btThreadStatus - { - int m_taskId; - int m_commandId; - int m_status; - - ThreadFunc m_userThreadFunc; - void* m_userPtr; //for taskDesc etc - - void* m_threadHandle; //this one is calling 'Win32ThreadFunc' - - void* m_eventStartHandle; - char m_eventStartHandleName[ 32 ]; - - void* m_eventCompleteHandle; - char m_eventCompleteHandleName[ 32 ]; - }; - -private: - btAlignedObjectArray m_activeThreadStatus; - btAlignedObjectArray m_completeHandles; - int m_numThreads; - DWORD_PTR m_startedThreadMask; - btProcessorInfo m_processorInfo; - - void startThreads( const ConstructionInfo& threadInfo ); - void stopThreads(); - int waitForResponse(); - -public: - - btThreadSupportWin32( const ConstructionInfo& threadConstructionInfo ); - virtual ~btThreadSupportWin32(); - - virtual int getNumWorkerThreads() const BT_OVERRIDE { return m_numThreads; } - virtual int getCacheFriendlyNumThreads() const BT_OVERRIDE { return countSetBits(m_processorInfo.processorTeamMasks[0]); } - virtual int getLogicalToPhysicalCoreRatio() const BT_OVERRIDE { return m_processorInfo.numLogicalProcessors / m_processorInfo.numCores; } - - virtual void runTask( int threadIndex, void* userData ) BT_OVERRIDE; - virtual void waitForAllTasks() BT_OVERRIDE; - - virtual btCriticalSection* createCriticalSection() BT_OVERRIDE; - virtual void deleteCriticalSection( btCriticalSection* criticalSection ) BT_OVERRIDE; -}; - - -btThreadSupportWin32::btThreadSupportWin32( const ConstructionInfo & threadConstructionInfo ) -{ - startThreads( threadConstructionInfo ); -} - - -btThreadSupportWin32::~btThreadSupportWin32() -{ - stopThreads(); -} - - -DWORD WINAPI win32threadStartFunc( LPVOID lpParam ) -{ - btThreadSupportWin32::btThreadStatus* status = ( btThreadSupportWin32::btThreadStatus* )lpParam; - - while ( 1 ) - { - WaitForSingleObject( status->m_eventStartHandle, INFINITE ); - void* userPtr = status->m_userPtr; - - if ( userPtr ) - { - btAssert( status->m_status ); - status->m_userThreadFunc( userPtr ); - status->m_status = 2; - SetEvent( status->m_eventCompleteHandle ); - } - else - { - //exit Thread - status->m_status = 3; - printf( "Thread with taskId %i with handle %p exiting\n", status->m_taskId, status->m_threadHandle ); - SetEvent( status->m_eventCompleteHandle ); - break; - } - } - printf( "Thread TERMINATED\n" ); - return 0; -} - - -void btThreadSupportWin32::runTask( int threadIndex, void* userData ) -{ - btThreadStatus& threadStatus = m_activeThreadStatus[ threadIndex ]; - btAssert( threadIndex >= 0 ); - btAssert( int( threadIndex ) < m_activeThreadStatus.size() ); - - threadStatus.m_commandId = 1; - threadStatus.m_status = 1; - threadStatus.m_userPtr = userData; - m_startedThreadMask |= DWORD_PTR( 1 ) << threadIndex; - - ///fire event to start new task - SetEvent( threadStatus.m_eventStartHandle ); -} - - -int btThreadSupportWin32::waitForResponse() -{ - btAssert( m_activeThreadStatus.size() ); - - int last = -1; - DWORD res = WaitForMultipleObjects( m_completeHandles.size(), &m_completeHandles[ 0 ], FALSE, INFINITE ); - btAssert( res != WAIT_FAILED ); - last = res - WAIT_OBJECT_0; - - btThreadStatus& threadStatus = m_activeThreadStatus[ last ]; - btAssert( threadStatus.m_threadHandle ); - btAssert( threadStatus.m_eventCompleteHandle ); - - //WaitForSingleObject(threadStatus.m_eventCompleteHandle, INFINITE); - btAssert( threadStatus.m_status > 1 ); - threadStatus.m_status = 0; - - ///need to find an active spu - btAssert( last >= 0 ); - m_startedThreadMask &= ~( DWORD_PTR( 1 ) << last ); - - return last; -} - - -void btThreadSupportWin32::waitForAllTasks() -{ - while ( m_startedThreadMask ) - { - waitForResponse(); - } -} - - -void btThreadSupportWin32::startThreads( const ConstructionInfo& threadConstructionInfo ) -{ - static int uniqueId = 0; - uniqueId++; - btProcessorInfo& procInfo = m_processorInfo; - getProcessorInformation( &procInfo ); - DWORD_PTR dwProcessAffinityMask = 0; - DWORD_PTR dwSystemAffinityMask = 0; - if ( !GetProcessAffinityMask( GetCurrentProcess(), &dwProcessAffinityMask, &dwSystemAffinityMask ) ) - { - dwProcessAffinityMask = 0; - } - ///The number of threads should be equal to the number of available cores - 1 - m_numThreads = btMin(procInfo.numLogicalProcessors, int(BT_MAX_THREAD_COUNT)) - 1; // cap to max thread count (-1 because main thread already exists) - - m_activeThreadStatus.resize( m_numThreads ); - m_completeHandles.resize( m_numThreads ); - m_startedThreadMask = 0; - - // set main thread affinity - if ( DWORD_PTR mask = dwProcessAffinityMask & getProcessorTeamMask( procInfo, 0 )) - { - SetThreadAffinityMask( GetCurrentThread(), mask ); - SetThreadIdealProcessor( GetCurrentThread(), 0 ); - } - - for ( int i = 0; i < m_numThreads; i++ ) - { - printf( "starting thread %d\n", i ); - - btThreadStatus& threadStatus = m_activeThreadStatus[ i ]; - - LPSECURITY_ATTRIBUTES lpThreadAttributes = NULL; - SIZE_T dwStackSize = threadConstructionInfo.m_threadStackSize; - LPTHREAD_START_ROUTINE lpStartAddress = &win32threadStartFunc; - LPVOID lpParameter = &threadStatus; - DWORD dwCreationFlags = 0; - LPDWORD lpThreadId = 0; - - threadStatus.m_userPtr = 0; - - sprintf( threadStatus.m_eventStartHandleName, "es%.8s%d%d", threadConstructionInfo.m_uniqueName, uniqueId, i ); - threadStatus.m_eventStartHandle = CreateEventA( 0, false, false, threadStatus.m_eventStartHandleName ); - - sprintf( threadStatus.m_eventCompleteHandleName, "ec%.8s%d%d", threadConstructionInfo.m_uniqueName, uniqueId, i ); - threadStatus.m_eventCompleteHandle = CreateEventA( 0, false, false, threadStatus.m_eventCompleteHandleName ); - - m_completeHandles[ i ] = threadStatus.m_eventCompleteHandle; - - HANDLE handle = CreateThread( lpThreadAttributes, dwStackSize, lpStartAddress, lpParameter, dwCreationFlags, lpThreadId ); - //SetThreadPriority( handle, THREAD_PRIORITY_HIGHEST ); - // highest priority -- can cause erratic performance when numThreads > numCores - // we don't want worker threads to be higher priority than the main thread or the main thread could get - // totally shut out and unable to tell the workers to stop - //SetThreadPriority( handle, THREAD_PRIORITY_BELOW_NORMAL ); - - { - int processorId = i + 1; // leave processor 0 for main thread - DWORD_PTR teamMask = getProcessorTeamMask( procInfo, processorId ); - if ( teamMask ) - { - // bind each thread to only execute on processors of it's assigned team - // - for single-socket Intel x86 CPUs this has no effect (only a single, shared L3 cache so there is only 1 team) - // - for multi-socket Intel this will keep threads from migrating from one socket to another - // - for AMD Ryzen this will keep threads from migrating from one CCX to another - DWORD_PTR mask = teamMask & dwProcessAffinityMask; - if ( mask ) - { - SetThreadAffinityMask( handle, mask ); - } - } - SetThreadIdealProcessor( handle, processorId ); - } - - threadStatus.m_taskId = i; - threadStatus.m_commandId = 0; - threadStatus.m_status = 0; - threadStatus.m_threadHandle = handle; - threadStatus.m_userThreadFunc = threadConstructionInfo.m_userThreadFunc; - - printf( "started %s thread %d with threadHandle %p\n", threadConstructionInfo.m_uniqueName, i, handle ); - } -} - -///tell the task scheduler we are done with the SPU tasks -void btThreadSupportWin32::stopThreads() -{ - for ( int i = 0; i < m_activeThreadStatus.size(); i++ ) - { - btThreadStatus& threadStatus = m_activeThreadStatus[ i ]; - if ( threadStatus.m_status > 0 ) - { - WaitForSingleObject( threadStatus.m_eventCompleteHandle, INFINITE ); - } - - threadStatus.m_userPtr = NULL; - SetEvent( threadStatus.m_eventStartHandle ); - WaitForSingleObject( threadStatus.m_eventCompleteHandle, INFINITE ); - - CloseHandle( threadStatus.m_eventCompleteHandle ); - CloseHandle( threadStatus.m_eventStartHandle ); - CloseHandle( threadStatus.m_threadHandle ); - - } - - m_activeThreadStatus.clear(); - m_completeHandles.clear(); -} - - -class btWin32CriticalSection : public btCriticalSection -{ -private: - CRITICAL_SECTION mCriticalSection; - -public: - btWin32CriticalSection() - { - InitializeCriticalSection( &mCriticalSection ); - } - - ~btWin32CriticalSection() - { - DeleteCriticalSection( &mCriticalSection ); - } - - void lock() - { - EnterCriticalSection( &mCriticalSection ); - } - - void unlock() - { - LeaveCriticalSection( &mCriticalSection ); - } -}; - - -btCriticalSection* btThreadSupportWin32::createCriticalSection() -{ - unsigned char* mem = (unsigned char*) btAlignedAlloc( sizeof( btWin32CriticalSection ), 16 ); - btWin32CriticalSection* cs = new( mem ) btWin32CriticalSection(); - return cs; -} - -void btThreadSupportWin32::deleteCriticalSection( btCriticalSection* criticalSection ) -{ - criticalSection->~btCriticalSection(); - btAlignedFree( criticalSection ); -} - - -btThreadSupportInterface* btThreadSupportInterface::create( const ConstructionInfo& info ) -{ - return new btThreadSupportWin32( info ); -} - - - -#endif //defined(_WIN32) && BT_THREADSAFE - diff --git a/extern/bullet/src/LinearMath/btAlignedAllocator.cpp b/extern/bullet/src/LinearMath/btAlignedAllocator.cpp index 0526a42283fe..e5f6040c4382 100644 --- a/extern/bullet/src/LinearMath/btAlignedAllocator.cpp +++ b/extern/bullet/src/LinearMath/btAlignedAllocator.cpp @@ -15,11 +15,9 @@ subject to the following restrictions: #include "btAlignedAllocator.h" -#ifdef BT_DEBUG_MEMORY_ALLOCATIONS int gNumAlignedAllocs = 0; int gNumAlignedFree = 0; int gTotalBytesAlignedAllocs = 0;//detect memory leaks -#endif //BT_DEBUG_MEMORY_ALLOCATIONST_DEBUG_ALLOCATIONS static void *btAllocDefault(size_t size) { @@ -248,6 +246,7 @@ void btAlignedFreeInternal (void* ptr,int line,char* filename) void* btAlignedAllocInternal (size_t size, int alignment) { + gNumAlignedAllocs++; void* ptr; ptr = sAlignedAllocFunc(size, alignment); // printf("btAlignedAllocInternal %d, %x\n",size,ptr); @@ -261,6 +260,7 @@ void btAlignedFreeInternal (void* ptr) return; } + gNumAlignedFree++; // printf("btAlignedFreeInternal %x\n",ptr); sAlignedFreeFunc(ptr); } diff --git a/extern/bullet/src/LinearMath/btHashMap.h b/extern/bullet/src/LinearMath/btHashMap.h index 180e7b44afad..5e9cdb605481 100644 --- a/extern/bullet/src/LinearMath/btHashMap.h +++ b/extern/bullet/src/LinearMath/btHashMap.h @@ -17,13 +17,12 @@ subject to the following restrictions: #ifndef BT_HASH_MAP_H #define BT_HASH_MAP_H -#include #include "btAlignedObjectArray.h" ///very basic hashable string implementation, compatible with btHashMap struct btHashString { - std::string m_string1; + const char* m_string; unsigned int m_hash; SIMD_FORCE_INLINE unsigned int getHash()const @@ -31,13 +30,8 @@ struct btHashString return m_hash; } - btHashString() - { - m_string1=""; - m_hash=0; - } btHashString(const char* name) - :m_string1(name) + :m_string(name) { /* magic numbers from http://www.isthe.com/chongo/tech/comp/fnv/ */ static const unsigned int InitialFNV = 2166136261u; @@ -46,18 +40,36 @@ struct btHashString /* Fowler / Noll / Vo (FNV) Hash */ unsigned int hash = InitialFNV; - for(int i = 0; m_string1.c_str()[i]; i++) + for(int i = 0; m_string[i]; i++) { - hash = hash ^ (m_string1.c_str()[i]); /* xor the low 8 bits */ + hash = hash ^ (m_string[i]); /* xor the low 8 bits */ hash = hash * FNVMultiple; /* multiply by the magic number */ } m_hash = hash; } + int portableStringCompare(const char* src, const char* dst) const + { + int ret = 0 ; + + while( ! (ret = *(const unsigned char *)src - *(const unsigned char *)dst) && *dst) + ++src, ++dst; + + if ( ret < 0 ) + ret = -1 ; + else if ( ret > 0 ) + ret = 1 ; + + return( ret ); + } + bool equals(const btHashString& other) const { - return (m_string1 == other.m_string1); + return (m_string == other.m_string) || + (0==portableStringCompare(m_string,other.m_string)); + } + }; const int BT_HASH_NULL=0xffffffff; diff --git a/extern/bullet/src/LinearMath/btMatrix3x3.h b/extern/bullet/src/LinearMath/btMatrix3x3.h index 6cc4993da56e..9f642a1779ae 100644 --- a/extern/bullet/src/LinearMath/btMatrix3x3.h +++ b/extern/bullet/src/LinearMath/btMatrix3x3.h @@ -289,7 +289,7 @@ ATTRIBUTE_ALIGNED16(class) btMatrix3x3 { /** @brief Set the matrix from euler angles YPR around ZYX axes * @param eulerX Roll about X axis * @param eulerY Pitch around Y axis - * @param eulerZ Yaw about Z axis + * @param eulerZ Yaw aboud Z axis * * These angles are used to produce a rotation matrix. The euler * angles are applied in ZYX order. I.e a vector is first rotated @@ -514,7 +514,7 @@ ATTRIBUTE_ALIGNED16(class) btMatrix3x3 { /**@brief Get the matrix represented as euler angles around ZYX - * @param yaw Yaw around Z axis + * @param yaw Yaw around X axis * @param pitch Pitch around Y axis * @param roll around X axis * @param solution_number Which solution of two possible solutions ( 1 or 2) are possible values*/ @@ -649,10 +649,6 @@ ATTRIBUTE_ALIGNED16(class) btMatrix3x3 { ///extractRotation is from "A robust method to extract the rotational part of deformations" ///See http://dl.acm.org/citation.cfm?doid=2994258.2994269 - ///decomposes a matrix A in a orthogonal matrix R and a - ///symmetric matrix S: - ///A = R*S. - ///note that R can include both rotation and scaling. SIMD_FORCE_INLINE void extractRotation(btQuaternion &q,btScalar tolerance = 1.0e-9, int maxIter=100) { int iter =0; @@ -677,96 +673,28 @@ ATTRIBUTE_ALIGNED16(class) btMatrix3x3 { - - /**@brief diagonalizes this matrix by the Jacobi method. + /**@brief diagonalizes this matrix * @param rot stores the rotation from the coordinate system in which the matrix is diagonal to the original - * coordinate system, i.e., old_this = rot * new_this * rot^T. + * coordinate system, i.e., old_this = rot * new_this * rot^T. * @param threshold See iteration - * @param iteration The iteration stops when all off-diagonal elements are less than the threshold multiplied - * by the sum of the absolute values of the diagonal, or when maxSteps have been executed. - * - * Note that this matrix is assumed to be symmetric. + * @param maxIter The iteration stops when we hit the given tolerance or when maxIter have been executed. */ - void diagonalize(btMatrix3x3& rot, btScalar threshold, int maxSteps) + void diagonalize(btMatrix3x3& rot, btScalar tolerance = 1.0e-9, int maxIter=100) { - rot.setIdentity(); - for (int step = maxSteps; step > 0; step--) - { - // find off-diagonal element [p][q] with largest magnitude - int p = 0; - int q = 1; - int r = 2; - btScalar max = btFabs(m_el[0][1]); - btScalar v = btFabs(m_el[0][2]); - if (v > max) - { - q = 2; - r = 1; - max = v; - } - v = btFabs(m_el[1][2]); - if (v > max) - { - p = 1; - q = 2; - r = 0; - max = v; - } - - btScalar t = threshold * (btFabs(m_el[0][0]) + btFabs(m_el[1][1]) + btFabs(m_el[2][2])); - if (max <= t) - { - if (max <= SIMD_EPSILON * t) - { - return; - } - step = 1; - } - - // compute Jacobi rotation J which leads to a zero for element [p][q] - btScalar mpq = m_el[p][q]; - btScalar theta = (m_el[q][q] - m_el[p][p]) / (2 * mpq); - btScalar theta2 = theta * theta; - btScalar cos; - btScalar sin; - if (theta2 * theta2 < btScalar(10 / SIMD_EPSILON)) - { - t = (theta >= 0) ? 1 / (theta + btSqrt(1 + theta2)) - : 1 / (theta - btSqrt(1 + theta2)); - cos = 1 / btSqrt(1 + t * t); - sin = cos * t; - } - else - { - // approximation for large theta-value, i.e., a nearly diagonal matrix - t = 1 / (theta * (2 + btScalar(0.5) / theta2)); - cos = 1 - btScalar(0.5) * t * t; - sin = cos * t; - } - - // apply rotation to matrix (this = J^T * this * J) - m_el[p][q] = m_el[q][p] = 0; - m_el[p][p] -= t * mpq; - m_el[q][q] += t * mpq; - btScalar mrp = m_el[r][p]; - btScalar mrq = m_el[r][q]; - m_el[r][p] = m_el[p][r] = cos * mrp - sin * mrq; - m_el[r][q] = m_el[q][r] = cos * mrq + sin * mrp; - - // apply rotation to rot (rot = rot * J) - for (int i = 0; i < 3; i++) - { - btVector3& row = rot[i]; - mrp = row[p]; - mrq = row[q]; - row[p] = cos * mrp - sin * mrq; - row[q] = cos * mrq + sin * mrp; - } - } + btQuaternion r; + r = btQuaternion::getIdentity(); + extractRotation(r,tolerance,maxIter); + rot.setRotation(r); + btMatrix3x3 rotInv = btMatrix3x3(r.inverse()); + btMatrix3x3 old = *this; + setValue(old.tdotx( rotInv[0]), old.tdoty( rotInv[0]), old.tdotz( rotInv[0]), + old.tdotx( rotInv[1]), old.tdoty( rotInv[1]), old.tdotz( rotInv[1]), + old.tdotx( rotInv[2]), old.tdoty( rotInv[2]), old.tdotz( rotInv[2])); } + /**@brief Calculate the matrix cofactor * @param r1 The first row to use for calculating the cofactor * @param c1 The first column to use for calculating the cofactor diff --git a/extern/bullet/src/LinearMath/btQuaternion.h b/extern/bullet/src/LinearMath/btQuaternion.h index a98fec7bc477..7bd39e6a3316 100644 --- a/extern/bullet/src/LinearMath/btQuaternion.h +++ b/extern/bullet/src/LinearMath/btQuaternion.h @@ -173,28 +173,10 @@ class btQuaternion : public btQuadWord { sqy = m_floats[1] * m_floats[1]; sqz = m_floats[2] * m_floats[2]; squ = m_floats[3] * m_floats[3]; - sarg = btScalar(-2.) * (m_floats[0] * m_floats[2] - m_floats[3] * m_floats[1]); - - // If the pitch angle is PI/2 or -PI/2, we can only compute - // the sum roll + yaw. However, any combination that gives - // the right sum will produce the correct orientation, so we - // set rollX = 0 and compute yawZ. - if (sarg <= -btScalar(0.99999)) - { - pitchY = btScalar(-0.5)*SIMD_PI; - rollX = 0; - yawZ = btScalar(2) * btAtan2(m_floats[0],-m_floats[1]); - } else if (sarg >= btScalar(0.99999)) - { - pitchY = btScalar(0.5)*SIMD_PI; - rollX = 0; - yawZ = btScalar(2) * btAtan2(-m_floats[0], m_floats[1]); - } else - { - pitchY = btAsin(sarg); - rollX = btAtan2(2 * (m_floats[1] * m_floats[2] + m_floats[3] * m_floats[0]), squ - sqx - sqy + sqz); - yawZ = btAtan2(2 * (m_floats[0] * m_floats[1] + m_floats[3] * m_floats[2]), squ + sqx - sqy - sqz); - } + rollX = btAtan2(2 * (m_floats[1] * m_floats[2] + m_floats[3] * m_floats[0]), squ - sqx - sqy + sqz); + sarg = btScalar(-2.) * (m_floats[0] * m_floats[2] - m_floats[3] * m_floats[1]); + pitchY = sarg <= btScalar(-1.0) ? btScalar(-0.5) * SIMD_PI: (sarg >= btScalar(1.0) ? btScalar(0.5) * SIMD_PI : btAsin(sarg)); + yawZ = btAtan2(2 * (m_floats[0] * m_floats[1] + m_floats[3] * m_floats[2]), squ + sqx - sqy - sqz); } /**@brief Add two quaternions @@ -620,9 +602,7 @@ class btQuaternion : public btQuadWord { SIMD_FORCE_INLINE void serialize(struct btQuaternionData& dataOut) const; - SIMD_FORCE_INLINE void deSerialize(const struct btQuaternionFloatData& dataIn); - - SIMD_FORCE_INLINE void deSerialize(const struct btQuaternionDoubleData& dataIn); + SIMD_FORCE_INLINE void deSerialize(const struct btQuaternionData& dataIn); SIMD_FORCE_INLINE void serializeFloat(struct btQuaternionFloatData& dataOut) const; @@ -1023,16 +1003,10 @@ SIMD_FORCE_INLINE void btQuaternion::serialize(struct btQuaternionData& dataOut) dataOut.m_floats[i] = m_floats[i]; } -SIMD_FORCE_INLINE void btQuaternion::deSerialize(const struct btQuaternionFloatData& dataIn) -{ - for (int i = 0; i<4; i++) - m_floats[i] = (btScalar)dataIn.m_floats[i]; -} - -SIMD_FORCE_INLINE void btQuaternion::deSerialize(const struct btQuaternionDoubleData& dataIn) +SIMD_FORCE_INLINE void btQuaternion::deSerialize(const struct btQuaternionData& dataIn) { for (int i=0;i<4;i++) - m_floats[i] = (btScalar)dataIn.m_floats[i]; + m_floats[i] = dataIn.m_floats[i]; } diff --git a/extern/bullet/src/LinearMath/btQuickprof.cpp b/extern/bullet/src/LinearMath/btQuickprof.cpp index 1572b9626226..aed3104a6e25 100644 --- a/extern/bullet/src/LinearMath/btQuickprof.cpp +++ b/extern/bullet/src/LinearMath/btQuickprof.cpp @@ -680,58 +680,56 @@ void CProfileManager::dumpAll() CProfileManager::Release_Iterator(profileIterator); } -// clang-format off -#if defined(_WIN32) && (defined(__MINGW32__) || defined(__MINGW64__)) - #define BT_HAVE_TLS 1 -#elif __APPLE__ && !TARGET_OS_IPHONE - // TODO: Modern versions of iOS support TLS now with updated version checking. - #define BT_HAVE_TLS 1 -#elif __linux__ - #define BT_HAVE_TLS 1 -#endif -// __thread is broken on Andorid clang until r12b. See -// https://github.com/android-ndk/ndk/issues/8 -#if defined(__ANDROID__) && defined(__clang__) - #if __has_include() - #include - #endif // __has_include() - #if defined(__NDK_MAJOR__) && \ - ((__NDK_MAJOR__ < 12) || ((__NDK_MAJOR__ == 12) && (__NDK_MINOR__ < 1))) - #undef BT_HAVE_TLS - #endif -#endif // defined(__ANDROID__) && defined(__clang__) -// clang-format on - -unsigned int btQuickprofGetCurrentThreadIndex2() { - const unsigned int kNullIndex = ~0U; + +unsigned int btQuickprofGetCurrentThreadIndex2() +{ #if BT_THREADSAFE - return btGetCurrentThreadIndex(); + return btGetCurrentThreadIndex(); +#else // #if BT_THREADSAFE + const unsigned int kNullIndex = ~0U; +#ifdef _WIN32 + #if defined(__MINGW32__) || defined(__MINGW64__) + static __thread unsigned int sThreadIndex = kNullIndex; + #else + __declspec( thread ) static unsigned int sThreadIndex = kNullIndex; + #endif #else -#if defined(BT_HAVE_TLS) - static __thread unsigned int sThreadIndex = kNullIndex; -#elif defined(_WIN32) - __declspec(thread) static unsigned int sThreadIndex = kNullIndex; +#ifdef __APPLE__ + #if TARGET_OS_IPHONE + unsigned int sThreadIndex = 0; + return -1; + #else + static __thread unsigned int sThreadIndex = kNullIndex; + #endif +#else//__APPLE__ +#if __linux__ + static __thread unsigned int sThreadIndex = kNullIndex; #else - unsigned int sThreadIndex = 0; - return -1; + unsigned int sThreadIndex = 0; + return -1; #endif +#endif//__APPLE__ + +#endif + static int gThreadCounter=0; - static int gThreadCounter = 0; - - if (sThreadIndex == kNullIndex) { - sThreadIndex = gThreadCounter++; - } - return sThreadIndex; -#endif //BT_THREADSAFE + if ( sThreadIndex == kNullIndex ) + { + sThreadIndex = gThreadCounter++; + } + return sThreadIndex; +#endif // #else // #if BT_THREADSAFE } void btEnterProfileZoneDefault(const char* name) { + CProfileManager::Start_Profile( name ); } void btLeaveProfileZoneDefault() { + CProfileManager::Stop_Profile(); } diff --git a/extern/bullet/src/LinearMath/btQuickprof.h b/extern/bullet/src/LinearMath/btQuickprof.h index 98a267577146..7b38d71b90db 100644 --- a/extern/bullet/src/LinearMath/btQuickprof.h +++ b/extern/bullet/src/LinearMath/btQuickprof.h @@ -70,12 +70,11 @@ void btSetCustomLeaveProfileZoneFunc(btLeaveProfileZoneFunc* leaveFunc); //#define BT_NO_PROFILE 1 #endif //BT_NO_PROFILE -const unsigned int BT_QUICKPROF_MAX_THREAD_COUNT = 64; - #ifndef BT_NO_PROFILE //btQuickprofGetCurrentThreadIndex will return -1 if thread index cannot be determined, //otherwise returns thread index in range [0..maxThreads] unsigned int btQuickprofGetCurrentThreadIndex2(); +const unsigned int BT_QUICKPROF_MAX_THREAD_COUNT = 64; #include //@todo remove this, backwards compatibility diff --git a/extern/bullet/src/LinearMath/btScalar.h b/extern/bullet/src/LinearMath/btScalar.h index 24e8454c1f2f..47b00385057b 100644 --- a/extern/bullet/src/LinearMath/btScalar.h +++ b/extern/bullet/src/LinearMath/btScalar.h @@ -14,6 +14,9 @@ subject to the following restrictions: #ifndef BT_SCALAR_H #define BT_SCALAR_H +#if defined(_MSC_VER) && defined(__clang__) /* clang supplies it's own overloads already */ +#define BT_NO_SIMD_OPERATOR_OVERLOADS +#endif #ifdef BT_MANAGED_CODE //Aligned data types not supported in managed code @@ -25,7 +28,7 @@ subject to the following restrictions: #include /* SVN $Revision$ on $Date$ from http://bullet.googlecode.com*/ -#define BT_BULLET_VERSION 288 +#define BT_BULLET_VERSION 287 inline int btGetVersion() { @@ -101,7 +104,7 @@ inline int btGetVersion() #ifdef BT_USE_SSE #if (_MSC_FULL_VER >= 170050727)//Visual Studio 2012 can compile SSE4/FMA3 (but SSE4/FMA3 is not enabled by default) - #define BT_ALLOW_SSE4 + //#define BT_ALLOW_SSE4 //disable this cause blender targets sse2 #endif //(_MSC_FULL_VER >= 160040219) //BT_USE_SSE_IN_API is disabled under Windows by default, because diff --git a/extern/bullet/src/LinearMath/btSerializer.cpp b/extern/bullet/src/LinearMath/btSerializer.cpp index 4faa8f536bfa..fcd2255ad566 100644 --- a/extern/bullet/src/LinearMath/btSerializer.cpp +++ b/extern/bullet/src/LinearMath/btSerializer.cpp @@ -1,5 +1,5 @@ char sBulletDNAstr[]= { -char(83),char(68),char(78),char(65),char(78),char(65),char(77),char(69),char(-76),char(1),char(0),char(0),char(109),char(95),char(115),char(105),char(122),char(101),char(0),char(109), +char(83),char(68),char(78),char(65),char(78),char(65),char(77),char(69),char(-124),char(1),char(0),char(0),char(109),char(95),char(115),char(105),char(122),char(101),char(0),char(109), char(95),char(99),char(97),char(112),char(97),char(99),char(105),char(116),char(121),char(0),char(42),char(109),char(95),char(100),char(97),char(116),char(97),char(0),char(109),char(95), char(99),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(83),char(104),char(97),char(112),char(101),char(115),char(0),char(109),char(95),char(99),char(111), char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(79),char(98),char(106),char(101),char(99),char(116),char(115),char(0),char(109),char(95),char(99),char(111),char(110), @@ -72,618 +72,528 @@ char(105),char(115),char(116),char(97),char(110),char(99),char(101),char(84),cha char(101),char(114),char(111),char(65),char(114),char(101),char(97),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(0),char(109),char(95),char(110), char(101),char(120),char(116),char(83),char(105),char(122),char(101),char(0),char(109),char(95),char(104),char(97),char(115),char(104),char(84),char(97),char(98),char(108),char(101),char(83), char(105),char(122),char(101),char(0),char(109),char(95),char(110),char(117),char(109),char(86),char(97),char(108),char(117),char(101),char(115),char(0),char(109),char(95),char(110),char(117), -char(109),char(75),char(101),char(121),char(115),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(76),char(111), -char(99),char(97),char(108),char(80),char(111),char(105),char(110),char(116),char(65),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116), -char(67),char(97),char(99),char(104),char(101),char(76),char(111),char(99),char(97),char(108),char(80),char(111),char(105),char(110),char(116),char(66),char(91),char(52),char(93),char(0), -char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(80),char(111),char(115),char(105),char(116),char(105),char(111),char(110), -char(87),char(111),char(114),char(108),char(100),char(79),char(110),char(65),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67), -char(97),char(99),char(104),char(101),char(80),char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(87),char(111),char(114),char(108),char(100),char(79),char(110),char(66), -char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(78),char(111),char(114),char(109), -char(97),char(108),char(87),char(111),char(114),char(108),char(100),char(79),char(110),char(66),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110), -char(116),char(67),char(97),char(99),char(104),char(101),char(76),char(97),char(116),char(101),char(114),char(97),char(108),char(70),char(114),char(105),char(99),char(116),char(105),char(111), -char(110),char(68),char(105),char(114),char(49),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104), -char(101),char(76),char(97),char(116),char(101),char(114),char(97),char(108),char(70),char(114),char(105),char(99),char(116),char(105),char(111),char(110),char(68),char(105),char(114),char(50), -char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(68),char(105),char(115),char(116), -char(97),char(110),char(99),char(101),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101), -char(65),char(112),char(112),char(108),char(105),char(101),char(100),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(91),char(52),char(93),char(0),char(109),char(95), -char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(67),char(111),char(109),char(98),char(105),char(110),char(101),char(100),char(70),char(114), -char(105),char(99),char(116),char(105),char(111),char(110),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99), -char(104),char(101),char(67),char(111),char(109),char(98),char(105),char(110),char(101),char(100),char(82),char(111),char(108),char(108),char(105),char(110),char(103),char(70),char(114),char(105), -char(99),char(116),char(105),char(111),char(110),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104), -char(101),char(67),char(111),char(109),char(98),char(105),char(110),char(101),char(100),char(83),char(112),char(105),char(110),char(110),char(105),char(110),char(103),char(70),char(114),char(105), -char(99),char(116),char(105),char(111),char(110),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104), -char(101),char(67),char(111),char(109),char(98),char(105),char(110),char(101),char(100),char(82),char(101),char(115),char(116),char(105),char(116),char(117),char(116),char(105),char(111),char(110), -char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(80),char(97),char(114),char(116), -char(73),char(100),char(48),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(80), -char(97),char(114),char(116),char(73),char(100),char(49),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99), -char(104),char(101),char(73),char(110),char(100),char(101),char(120),char(48),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67), -char(97),char(99),char(104),char(101),char(73),char(110),char(100),char(101),char(120),char(49),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110), -char(116),char(67),char(97),char(99),char(104),char(101),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(80),char(111),char(105),char(110),char(116),char(70),char(108), -char(97),char(103),char(115),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(65), -char(112),char(112),char(108),char(105),char(101),char(100),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(76),char(97),char(116),char(101),char(114),char(97),char(108), -char(49),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(65),char(112),char(112), -char(108),char(105),char(101),char(100),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(76),char(97),char(116),char(101),char(114),char(97),char(108),char(50),char(91), -char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(67),char(111),char(110),char(116),char(97), -char(99),char(116),char(77),char(111),char(116),char(105),char(111),char(110),char(49),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116), -char(67),char(97),char(99),char(104),char(101),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(77),char(111),char(116),char(105),char(111),char(110),char(50),char(91), -char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(67),char(111),char(110),char(116),char(97), -char(99),char(116),char(67),char(70),char(77),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104), -char(101),char(67),char(111),char(109),char(98),char(105),char(110),char(101),char(100),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(83),char(116),char(105),char(102), -char(102),char(110),char(101),char(115),char(115),char(49),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99), -char(104),char(101),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(69),char(82),char(80),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111), -char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(67),char(111),char(109),char(98),char(105),char(110),char(101),char(100),char(67),char(111),char(110),char(116), -char(97),char(99),char(116),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(49),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105), -char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(70),char(114),char(105),char(99),char(116),char(105),char(111),char(110),char(67),char(70),char(77),char(91),char(52), -char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(76),char(105),char(102),char(101),char(84),char(105), -char(109),char(101),char(91),char(52),char(93),char(0),char(109),char(95),char(110),char(117),char(109),char(67),char(97),char(99),char(104),char(101),char(100),char(80),char(111),char(105), -char(110),char(116),char(115),char(0),char(109),char(95),char(99),char(111),char(109),char(112),char(97),char(110),char(105),char(111),char(110),char(73),char(100),char(65),char(0),char(109), -char(95),char(99),char(111),char(109),char(112),char(97),char(110),char(105),char(111),char(110),char(73),char(100),char(66),char(0),char(109),char(95),char(105),char(110),char(100),char(101), -char(120),char(49),char(97),char(0),char(109),char(95),char(111),char(98),char(106),char(101),char(99),char(116),char(84),char(121),char(112),char(101),char(0),char(109),char(95),char(99), -char(111),char(110),char(116),char(97),char(99),char(116),char(66),char(114),char(101),char(97),char(107),char(105),char(110),char(103),char(84),char(104),char(114),char(101),char(115),char(104), -char(111),char(108),char(100),char(0),char(109),char(95),char(99),char(111),char(110),char(116),char(97),char(99),char(116),char(80),char(114),char(111),char(99),char(101),char(115),char(115), -char(105),char(110),char(103),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(0),char(42),char(109),char(95),char(98),char(111),char(100),char(121), -char(48),char(0),char(42),char(109),char(95),char(98),char(111),char(100),char(121),char(49),char(0),char(109),char(95),char(103),char(105),char(109),char(112),char(97),char(99),char(116), -char(83),char(117),char(98),char(84),char(121),char(112),char(101),char(0),char(42),char(109),char(95),char(117),char(110),char(115),char(99),char(97),char(108),char(101),char(100),char(80), -char(111),char(105),char(110),char(116),char(115),char(70),char(108),char(111),char(97),char(116),char(80),char(116),char(114),char(0),char(42),char(109),char(95),char(117),char(110),char(115), -char(99),char(97),char(108),char(101),char(100),char(80),char(111),char(105),char(110),char(116),char(115),char(68),char(111),char(117),char(98),char(108),char(101),char(80),char(116),char(114), -char(0),char(109),char(95),char(110),char(117),char(109),char(85),char(110),char(115),char(99),char(97),char(108),char(101),char(100),char(80),char(111),char(105),char(110),char(116),char(115), -char(0),char(109),char(95),char(112),char(97),char(100),char(100),char(105),char(110),char(103),char(51),char(91),char(52),char(93),char(0),char(42),char(109),char(95),char(98),char(114), -char(111),char(97),char(100),char(112),char(104),char(97),char(115),char(101),char(72),char(97),char(110),char(100),char(108),char(101),char(0),char(42),char(109),char(95),char(99),char(111), -char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(83),char(104),char(97),char(112),char(101),char(0),char(42),char(109),char(95),char(114),char(111),char(111),char(116), -char(67),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(83),char(104),char(97),char(112),char(101),char(0),char(109),char(95),char(119),char(111),char(114), -char(108),char(100),char(84),char(114),char(97),char(110),char(115),char(102),char(111),char(114),char(109),char(0),char(109),char(95),char(105),char(110),char(116),char(101),char(114),char(112), -char(111),char(108),char(97),char(116),char(105),char(111),char(110),char(87),char(111),char(114),char(108),char(100),char(84),char(114),char(97),char(110),char(115),char(102),char(111),char(114), -char(109),char(0),char(109),char(95),char(105),char(110),char(116),char(101),char(114),char(112),char(111),char(108),char(97),char(116),char(105),char(111),char(110),char(76),char(105),char(110), -char(101),char(97),char(114),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109),char(95),char(105),char(110),char(116),char(101),char(114),char(112), -char(111),char(108),char(97),char(116),char(105),char(111),char(110),char(65),char(110),char(103),char(117),char(108),char(97),char(114),char(86),char(101),char(108),char(111),char(99),char(105), -char(116),char(121),char(0),char(109),char(95),char(97),char(110),char(105),char(115),char(111),char(116),char(114),char(111),char(112),char(105),char(99),char(70),char(114),char(105),char(99), -char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(100),char(101),char(97),char(99),char(116),char(105),char(118),char(97),char(116),char(105),char(111),char(110),char(84), -char(105),char(109),char(101),char(0),char(109),char(95),char(102),char(114),char(105),char(99),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(114),char(111),char(108), -char(108),char(105),char(110),char(103),char(70),char(114),char(105),char(99),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(99),char(111),char(110),char(116),char(97), -char(99),char(116),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(0),char(109),char(95),char(99),char(111),char(110),char(116),char(97),char(99),char(116),char(83), -char(116),char(105),char(102),char(102),char(110),char(101),char(115),char(115),char(0),char(109),char(95),char(114),char(101),char(115),char(116),char(105),char(116),char(117),char(116),char(105), -char(111),char(110),char(0),char(109),char(95),char(104),char(105),char(116),char(70),char(114),char(97),char(99),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(99), -char(99),char(100),char(83),char(119),char(101),char(112),char(116),char(83),char(112),char(104),char(101),char(114),char(101),char(82),char(97),char(100),char(105),char(117),char(115),char(0), -char(109),char(95),char(99),char(99),char(100),char(77),char(111),char(116),char(105),char(111),char(110),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100), -char(0),char(109),char(95),char(104),char(97),char(115),char(65),char(110),char(105),char(115),char(111),char(116),char(114),char(111),char(112),char(105),char(99),char(70),char(114),char(105), -char(99),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(99),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(70),char(108),char(97), -char(103),char(115),char(0),char(109),char(95),char(105),char(115),char(108),char(97),char(110),char(100),char(84),char(97),char(103),char(49),char(0),char(109),char(95),char(99),char(111), -char(109),char(112),char(97),char(110),char(105),char(111),char(110),char(73),char(100),char(0),char(109),char(95),char(97),char(99),char(116),char(105),char(118),char(97),char(116),char(105), -char(111),char(110),char(83),char(116),char(97),char(116),char(101),char(49),char(0),char(109),char(95),char(105),char(110),char(116),char(101),char(114),char(110),char(97),char(108),char(84), -char(121),char(112),char(101),char(0),char(109),char(95),char(99),char(104),char(101),char(99),char(107),char(67),char(111),char(108),char(108),char(105),char(100),char(101),char(87),char(105), -char(116),char(104),char(0),char(109),char(95),char(99),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(70),char(105),char(108),char(116),char(101),char(114), -char(71),char(114),char(111),char(117),char(112),char(0),char(109),char(95),char(99),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(70),char(105),char(108), -char(116),char(101),char(114),char(77),char(97),char(115),char(107),char(0),char(109),char(95),char(117),char(110),char(105),char(113),char(117),char(101),char(73),char(100),char(0),char(109), -char(95),char(116),char(97),char(117),char(0),char(109),char(95),char(100),char(97),char(109),char(112),char(105),char(110),char(103),char(0),char(109),char(95),char(116),char(105),char(109), -char(101),char(83),char(116),char(101),char(112),char(0),char(109),char(95),char(109),char(97),char(120),char(69),char(114),char(114),char(111),char(114),char(82),char(101),char(100),char(117), -char(99),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(115),char(111),char(114),char(0),char(109),char(95),char(101),char(114),char(112),char(0),char(109),char(95), -char(101),char(114),char(112),char(50),char(0),char(109),char(95),char(103),char(108),char(111),char(98),char(97),char(108),char(67),char(102),char(109),char(0),char(109),char(95),char(115), -char(112),char(108),char(105),char(116),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(80),char(101),char(110),char(101),char(116),char(114),char(97),char(116),char(105), -char(111),char(110),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(0),char(109),char(95),char(115),char(112),char(108),char(105),char(116),char(73), -char(109),char(112),char(117),char(108),char(115),char(101),char(84),char(117),char(114),char(110),char(69),char(114),char(112),char(0),char(109),char(95),char(108),char(105),char(110),char(101), -char(97),char(114),char(83),char(108),char(111),char(112),char(0),char(109),char(95),char(119),char(97),char(114),char(109),char(115),char(116),char(97),char(114),char(116),char(105),char(110), -char(103),char(70),char(97),char(99),char(116),char(111),char(114),char(0),char(109),char(95),char(109),char(97),char(120),char(71),char(121),char(114),char(111),char(115),char(99),char(111), -char(112),char(105),char(99),char(70),char(111),char(114),char(99),char(101),char(0),char(109),char(95),char(115),char(105),char(110),char(103),char(108),char(101),char(65),char(120),char(105), -char(115),char(82),char(111),char(108),char(108),char(105),char(110),char(103),char(70),char(114),char(105),char(99),char(116),char(105),char(111),char(110),char(84),char(104),char(114),char(101), -char(115),char(104),char(111),char(108),char(100),char(0),char(109),char(95),char(110),char(117),char(109),char(73),char(116),char(101),char(114),char(97),char(116),char(105),char(111),char(110), -char(115),char(0),char(109),char(95),char(115),char(111),char(108),char(118),char(101),char(114),char(77),char(111),char(100),char(101),char(0),char(109),char(95),char(114),char(101),char(115), -char(116),char(105),char(110),char(103),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(82),char(101),char(115),char(116),char(105),char(116),char(117),char(116),char(105), -char(111),char(110),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(0),char(109),char(95),char(109),char(105),char(110),char(105),char(109),char(117), -char(109),char(83),char(111),char(108),char(118),char(101),char(114),char(66),char(97),char(116),char(99),char(104),char(83),char(105),char(122),char(101),char(0),char(109),char(95),char(115), -char(112),char(108),char(105),char(116),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(0),char(109),char(95),char(115),char(111),char(108),char(118),char(101),char(114), -char(73),char(110),char(102),char(111),char(0),char(109),char(95),char(103),char(114),char(97),char(118),char(105),char(116),char(121),char(0),char(109),char(95),char(99),char(111),char(108), -char(108),char(105),char(115),char(105),char(111),char(110),char(79),char(98),char(106),char(101),char(99),char(116),char(68),char(97),char(116),char(97),char(0),char(109),char(95),char(105), -char(110),char(118),char(73),char(110),char(101),char(114),char(116),char(105),char(97),char(84),char(101),char(110),char(115),char(111),char(114),char(87),char(111),char(114),char(108),char(100), -char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109),char(95), -char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109),char(95),char(97),char(110), -char(103),char(117),char(108),char(97),char(114),char(70),char(97),char(99),char(116),char(111),char(114),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114), -char(70),char(97),char(99),char(116),char(111),char(114),char(0),char(109),char(95),char(103),char(114),char(97),char(118),char(105),char(116),char(121),char(95),char(97),char(99),char(99), -char(101),char(108),char(101),char(114),char(97),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(105),char(110),char(118),char(73),char(110),char(101),char(114),char(116), -char(105),char(97),char(76),char(111),char(99),char(97),char(108),char(0),char(109),char(95),char(116),char(111),char(116),char(97),char(108),char(70),char(111),char(114),char(99),char(101), -char(0),char(109),char(95),char(116),char(111),char(116),char(97),char(108),char(84),char(111),char(114),char(113),char(117),char(101),char(0),char(109),char(95),char(105),char(110),char(118), -char(101),char(114),char(115),char(101),char(77),char(97),char(115),char(115),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(68),char(97),char(109), -char(112),char(105),char(110),char(103),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(68),char(97),char(109),char(112),char(105),char(110), -char(103),char(0),char(109),char(95),char(97),char(100),char(100),char(105),char(116),char(105),char(111),char(110),char(97),char(108),char(68),char(97),char(109),char(112),char(105),char(110), -char(103),char(70),char(97),char(99),char(116),char(111),char(114),char(0),char(109),char(95),char(97),char(100),char(100),char(105),char(116),char(105),char(111),char(110),char(97),char(108), -char(76),char(105),char(110),char(101),char(97),char(114),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(84),char(104),char(114),char(101),char(115),char(104),char(111), -char(108),char(100),char(83),char(113),char(114),char(0),char(109),char(95),char(97),char(100),char(100),char(105),char(116),char(105),char(111),char(110),char(97),char(108),char(65),char(110), -char(103),char(117),char(108),char(97),char(114),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108), -char(100),char(83),char(113),char(114),char(0),char(109),char(95),char(97),char(100),char(100),char(105),char(116),char(105),char(111),char(110),char(97),char(108),char(65),char(110),char(103), -char(117),char(108),char(97),char(114),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(70),char(97),char(99),char(116),char(111),char(114),char(0),char(109),char(95), -char(108),char(105),char(110),char(101),char(97),char(114),char(83),char(108),char(101),char(101),char(112),char(105),char(110),char(103),char(84),char(104),char(114),char(101),char(115),char(104), -char(111),char(108),char(100),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(83),char(108),char(101),char(101),char(112),char(105),char(110), -char(103),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(0),char(109),char(95),char(97),char(100),char(100),char(105),char(116),char(105),char(111), -char(110),char(97),char(108),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(0),char(109),char(95),char(110),char(117),char(109),char(67),char(111),char(110),char(115), -char(116),char(114),char(97),char(105),char(110),char(116),char(82),char(111),char(119),char(115),char(0),char(110),char(117),char(98),char(0),char(42),char(109),char(95),char(114),char(98), -char(65),char(0),char(42),char(109),char(95),char(114),char(98),char(66),char(0),char(109),char(95),char(117),char(115),char(101),char(114),char(67),char(111),char(110),char(115),char(116), -char(114),char(97),char(105),char(110),char(116),char(84),char(121),char(112),char(101),char(0),char(109),char(95),char(117),char(115),char(101),char(114),char(67),char(111),char(110),char(115), -char(116),char(114),char(97),char(105),char(110),char(116),char(73),char(100),char(0),char(109),char(95),char(110),char(101),char(101),char(100),char(115),char(70),char(101),char(101),char(100), -char(98),char(97),char(99),char(107),char(0),char(109),char(95),char(97),char(112),char(112),char(108),char(105),char(101),char(100),char(73),char(109),char(112),char(117),char(108),char(115), -char(101),char(0),char(109),char(95),char(100),char(98),char(103),char(68),char(114),char(97),char(119),char(83),char(105),char(122),char(101),char(0),char(109),char(95),char(100),char(105), -char(115),char(97),char(98),char(108),char(101),char(67),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(115),char(66),char(101),char(116),char(119),char(101), -char(101),char(110),char(76),char(105),char(110),char(107),char(101),char(100),char(66),char(111),char(100),char(105),char(101),char(115),char(0),char(109),char(95),char(111),char(118),char(101), -char(114),char(114),char(105),char(100),char(101),char(78),char(117),char(109),char(83),char(111),char(108),char(118),char(101),char(114),char(73),char(116),char(101),char(114),char(97),char(116), -char(105),char(111),char(110),char(115),char(0),char(109),char(95),char(98),char(114),char(101),char(97),char(107),char(105),char(110),char(103),char(73),char(109),char(112),char(117),char(108), -char(115),char(101),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(0),char(109),char(95),char(105),char(115),char(69),char(110),char(97),char(98), -char(108),char(101),char(100),char(0),char(112),char(97),char(100),char(100),char(105),char(110),char(103),char(91),char(52),char(93),char(0),char(109),char(95),char(116),char(121),char(112), -char(101),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(109),char(95),char(112),char(105), -char(118),char(111),char(116),char(73),char(110),char(65),char(0),char(109),char(95),char(112),char(105),char(118),char(111),char(116),char(73),char(110),char(66),char(0),char(109),char(95), -char(114),char(98),char(65),char(70),char(114),char(97),char(109),char(101),char(0),char(109),char(95),char(114),char(98),char(66),char(70),char(114),char(97),char(109),char(101),char(0), -char(109),char(95),char(117),char(115),char(101),char(82),char(101),char(102),char(101),char(114),char(101),char(110),char(99),char(101),char(70),char(114),char(97),char(109),char(101),char(65), -char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(79),char(110),char(108),char(121),char(0),char(109),char(95),char(101),char(110),char(97), -char(98),char(108),char(101),char(65),char(110),char(103),char(117),char(108),char(97),char(114),char(77),char(111),char(116),char(111),char(114),char(0),char(109),char(95),char(109),char(111), -char(116),char(111),char(114),char(84),char(97),char(114),char(103),char(101),char(116),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109),char(95), -char(109),char(97),char(120),char(77),char(111),char(116),char(111),char(114),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(0),char(109),char(95),char(108),char(111), -char(119),char(101),char(114),char(76),char(105),char(109),char(105),char(116),char(0),char(109),char(95),char(117),char(112),char(112),char(101),char(114),char(76),char(105),char(109),char(105), -char(116),char(0),char(109),char(95),char(108),char(105),char(109),char(105),char(116),char(83),char(111),char(102),char(116),char(110),char(101),char(115),char(115),char(0),char(109),char(95), -char(98),char(105),char(97),char(115),char(70),char(97),char(99),char(116),char(111),char(114),char(0),char(109),char(95),char(114),char(101),char(108),char(97),char(120),char(97),char(116), -char(105),char(111),char(110),char(70),char(97),char(99),char(116),char(111),char(114),char(0),char(109),char(95),char(112),char(97),char(100),char(100),char(105),char(110),char(103),char(49), -char(91),char(52),char(93),char(0),char(109),char(95),char(115),char(119),char(105),char(110),char(103),char(83),char(112),char(97),char(110),char(49),char(0),char(109),char(95),char(115), -char(119),char(105),char(110),char(103),char(83),char(112),char(97),char(110),char(50),char(0),char(109),char(95),char(116),char(119),char(105),char(115),char(116),char(83),char(112),char(97), -char(110),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(85),char(112),char(112),char(101),char(114),char(76),char(105),char(109),char(105),char(116), -char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(76),char(111),char(119),char(101),char(114),char(76),char(105),char(109),char(105),char(116),char(0), -char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(85),char(112),char(112),char(101),char(114),char(76),char(105),char(109),char(105),char(116),char(0), -char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(76),char(111),char(119),char(101),char(114),char(76),char(105),char(109),char(105),char(116),char(0), -char(109),char(95),char(117),char(115),char(101),char(76),char(105),char(110),char(101),char(97),char(114),char(82),char(101),char(102),char(101),char(114),char(101),char(110),char(99),char(101), -char(70),char(114),char(97),char(109),char(101),char(65),char(0),char(109),char(95),char(117),char(115),char(101),char(79),char(102),char(102),char(115),char(101),char(116),char(70),char(111), -char(114),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(114),char(97),char(109),char(101),char(0),char(109),char(95),char(54), -char(100),char(111),char(102),char(68),char(97),char(116),char(97),char(0),char(109),char(95),char(115),char(112),char(114),char(105),char(110),char(103),char(69),char(110),char(97),char(98), -char(108),char(101),char(100),char(91),char(54),char(93),char(0),char(109),char(95),char(101),char(113),char(117),char(105),char(108),char(105),char(98),char(114),char(105),char(117),char(109), -char(80),char(111),char(105),char(110),char(116),char(91),char(54),char(93),char(0),char(109),char(95),char(115),char(112),char(114),char(105),char(110),char(103),char(83),char(116),char(105), -char(102),char(102),char(110),char(101),char(115),char(115),char(91),char(54),char(93),char(0),char(109),char(95),char(115),char(112),char(114),char(105),char(110),char(103),char(68),char(97), -char(109),char(112),char(105),char(110),char(103),char(91),char(54),char(93),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(66),char(111),char(117), -char(110),char(99),char(101),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(83),char(116),char(111),char(112),char(69),char(82),char(80),char(0), -char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(83),char(116),char(111),char(112),char(67),char(70),char(77),char(0),char(109),char(95),char(108),char(105), -char(110),char(101),char(97),char(114),char(77),char(111),char(116),char(111),char(114),char(69),char(82),char(80),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97), -char(114),char(77),char(111),char(116),char(111),char(114),char(67),char(70),char(77),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(84),char(97), -char(114),char(103),char(101),char(116),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97), -char(114),char(77),char(97),char(120),char(77),char(111),char(116),char(111),char(114),char(70),char(111),char(114),char(99),char(101),char(0),char(109),char(95),char(108),char(105),char(110), -char(101),char(97),char(114),char(83),char(101),char(114),char(118),char(111),char(84),char(97),char(114),char(103),char(101),char(116),char(0),char(109),char(95),char(108),char(105),char(110), -char(101),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(83),char(116),char(105),char(102),char(102),char(110),char(101),char(115),char(115),char(0),char(109), -char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(68),char(97),char(109),char(112),char(105),char(110),char(103), -char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(69),char(113),char(117),char(105),char(108),char(105),char(98),char(114),char(105),char(117),char(109), -char(80),char(111),char(105),char(110),char(116),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(69),char(110),char(97),char(98),char(108),char(101), -char(77),char(111),char(116),char(111),char(114),char(91),char(52),char(93),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(83),char(101),char(114), -char(118),char(111),char(77),char(111),char(116),char(111),char(114),char(91),char(52),char(93),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(69), -char(110),char(97),char(98),char(108),char(101),char(83),char(112),char(114),char(105),char(110),char(103),char(91),char(52),char(93),char(0),char(109),char(95),char(108),char(105),char(110), -char(101),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(83),char(116),char(105),char(102),char(102),char(110),char(101),char(115),char(115),char(76),char(105), -char(109),char(105),char(116),char(101),char(100),char(91),char(52),char(93),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(83),char(112),char(114), -char(105),char(110),char(103),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(76),char(105),char(109),char(105),char(116),char(101),char(100),char(91),char(52),char(93), -char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(66),char(111),char(117),char(110),char(99),char(101),char(0),char(109),char(95),char(97), -char(110),char(103),char(117),char(108),char(97),char(114),char(83),char(116),char(111),char(112),char(69),char(82),char(80),char(0),char(109),char(95),char(97),char(110),char(103),char(117), -char(108),char(97),char(114),char(83),char(116),char(111),char(112),char(67),char(70),char(77),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114), -char(77),char(111),char(116),char(111),char(114),char(69),char(82),char(80),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(77),char(111), -char(116),char(111),char(114),char(67),char(70),char(77),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(84),char(97),char(114),char(103), -char(101),char(116),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114), -char(77),char(97),char(120),char(77),char(111),char(116),char(111),char(114),char(70),char(111),char(114),char(99),char(101),char(0),char(109),char(95),char(97),char(110),char(103),char(117), -char(108),char(97),char(114),char(83),char(101),char(114),char(118),char(111),char(84),char(97),char(114),char(103),char(101),char(116),char(0),char(109),char(95),char(97),char(110),char(103), -char(117),char(108),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(83),char(116),char(105),char(102),char(102),char(110),char(101),char(115),char(115),char(0), -char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(68),char(97),char(109),char(112),char(105), -char(110),char(103),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(69),char(113),char(117),char(105),char(108),char(105),char(98),char(114), -char(105),char(117),char(109),char(80),char(111),char(105),char(110),char(116),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(69),char(110), -char(97),char(98),char(108),char(101),char(77),char(111),char(116),char(111),char(114),char(91),char(52),char(93),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108), -char(97),char(114),char(83),char(101),char(114),char(118),char(111),char(77),char(111),char(116),char(111),char(114),char(91),char(52),char(93),char(0),char(109),char(95),char(97),char(110), -char(103),char(117),char(108),char(97),char(114),char(69),char(110),char(97),char(98),char(108),char(101),char(83),char(112),char(114),char(105),char(110),char(103),char(91),char(52),char(93), -char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(83),char(116),char(105),char(102), -char(102),char(110),char(101),char(115),char(115),char(76),char(105),char(109),char(105),char(116),char(101),char(100),char(91),char(52),char(93),char(0),char(109),char(95),char(97),char(110), -char(103),char(117),char(108),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(76),char(105), -char(109),char(105),char(116),char(101),char(100),char(91),char(52),char(93),char(0),char(109),char(95),char(114),char(111),char(116),char(97),char(116),char(101),char(79),char(114),char(100), -char(101),char(114),char(0),char(109),char(95),char(97),char(120),char(105),char(115),char(73),char(110),char(65),char(0),char(109),char(95),char(97),char(120),char(105),char(115),char(73), -char(110),char(66),char(0),char(109),char(95),char(114),char(97),char(116),char(105),char(111),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(83), -char(116),char(105),char(102),char(102),char(110),char(101),char(115),char(115),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(83),char(116), -char(105),char(102),char(102),char(110),char(101),char(115),char(115),char(0),char(109),char(95),char(118),char(111),char(108),char(117),char(109),char(101),char(83),char(116),char(105),char(102), -char(102),char(110),char(101),char(115),char(115),char(0),char(42),char(109),char(95),char(109),char(97),char(116),char(101),char(114),char(105),char(97),char(108),char(0),char(109),char(95), -char(112),char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(112),char(114),char(101),char(118),char(105),char(111),char(117),char(115),char(80), -char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(118),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109), -char(95),char(97),char(99),char(99),char(117),char(109),char(117),char(108),char(97),char(116),char(101),char(100),char(70),char(111),char(114),char(99),char(101),char(0),char(109),char(95), -char(110),char(111),char(114),char(109),char(97),char(108),char(0),char(109),char(95),char(97),char(114),char(101),char(97),char(0),char(109),char(95),char(97),char(116),char(116),char(97), -char(99),char(104),char(0),char(109),char(95),char(110),char(111),char(100),char(101),char(73),char(110),char(100),char(105),char(99),char(101),char(115),char(91),char(50),char(93),char(0), -char(109),char(95),char(114),char(101),char(115),char(116),char(76),char(101),char(110),char(103),char(116),char(104),char(0),char(109),char(95),char(98),char(98),char(101),char(110),char(100), -char(105),char(110),char(103),char(0),char(109),char(95),char(110),char(111),char(100),char(101),char(73),char(110),char(100),char(105),char(99),char(101),char(115),char(91),char(51),char(93), -char(0),char(109),char(95),char(114),char(101),char(115),char(116),char(65),char(114),char(101),char(97),char(0),char(109),char(95),char(99),char(48),char(91),char(52),char(93),char(0), -char(109),char(95),char(110),char(111),char(100),char(101),char(73),char(110),char(100),char(105),char(99),char(101),char(115),char(91),char(52),char(93),char(0),char(109),char(95),char(114), -char(101),char(115),char(116),char(86),char(111),char(108),char(117),char(109),char(101),char(0),char(109),char(95),char(99),char(49),char(0),char(109),char(95),char(99),char(50),char(0), -char(109),char(95),char(99),char(48),char(0),char(109),char(95),char(108),char(111),char(99),char(97),char(108),char(70),char(114),char(97),char(109),char(101),char(0),char(42),char(109), -char(95),char(114),char(105),char(103),char(105),char(100),char(66),char(111),char(100),char(121),char(0),char(109),char(95),char(110),char(111),char(100),char(101),char(73),char(110),char(100), -char(101),char(120),char(0),char(109),char(95),char(97),char(101),char(114),char(111),char(77),char(111),char(100),char(101),char(108),char(0),char(109),char(95),char(98),char(97),char(117), -char(109),char(103),char(97),char(114),char(116),char(101),char(0),char(109),char(95),char(100),char(114),char(97),char(103),char(0),char(109),char(95),char(108),char(105),char(102),char(116), -char(0),char(109),char(95),char(112),char(114),char(101),char(115),char(115),char(117),char(114),char(101),char(0),char(109),char(95),char(118),char(111),char(108),char(117),char(109),char(101), -char(0),char(109),char(95),char(100),char(121),char(110),char(97),char(109),char(105),char(99),char(70),char(114),char(105),char(99),char(116),char(105),char(111),char(110),char(0),char(109), -char(95),char(112),char(111),char(115),char(101),char(77),char(97),char(116),char(99),char(104),char(0),char(109),char(95),char(114),char(105),char(103),char(105),char(100),char(67),char(111), -char(110),char(116),char(97),char(99),char(116),char(72),char(97),char(114),char(100),char(110),char(101),char(115),char(115),char(0),char(109),char(95),char(107),char(105),char(110),char(101), -char(116),char(105),char(99),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(72),char(97),char(114),char(100),char(110),char(101),char(115),char(115),char(0),char(109), -char(95),char(115),char(111),char(102),char(116),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(72),char(97),char(114),char(100),char(110),char(101),char(115),char(115), -char(0),char(109),char(95),char(97),char(110),char(99),char(104),char(111),char(114),char(72),char(97),char(114),char(100),char(110),char(101),char(115),char(115),char(0),char(109),char(95), -char(115),char(111),char(102),char(116),char(82),char(105),char(103),char(105),char(100),char(67),char(108),char(117),char(115),char(116),char(101),char(114),char(72),char(97),char(114),char(100), -char(110),char(101),char(115),char(115),char(0),char(109),char(95),char(115),char(111),char(102),char(116),char(75),char(105),char(110),char(101),char(116),char(105),char(99),char(67),char(108), -char(117),char(115),char(116),char(101),char(114),char(72),char(97),char(114),char(100),char(110),char(101),char(115),char(115),char(0),char(109),char(95),char(115),char(111),char(102),char(116), -char(83),char(111),char(102),char(116),char(67),char(108),char(117),char(115),char(116),char(101),char(114),char(72),char(97),char(114),char(100),char(110),char(101),char(115),char(115),char(0), -char(109),char(95),char(115),char(111),char(102),char(116),char(82),char(105),char(103),char(105),char(100),char(67),char(108),char(117),char(115),char(116),char(101),char(114),char(73),char(109), -char(112),char(117),char(108),char(115),char(101),char(83),char(112),char(108),char(105),char(116),char(0),char(109),char(95),char(115),char(111),char(102),char(116),char(75),char(105),char(110), -char(101),char(116),char(105),char(99),char(67),char(108),char(117),char(115),char(116),char(101),char(114),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(83),char(112), -char(108),char(105),char(116),char(0),char(109),char(95),char(115),char(111),char(102),char(116),char(83),char(111),char(102),char(116),char(67),char(108),char(117),char(115),char(116),char(101), -char(114),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(83),char(112),char(108),char(105),char(116),char(0),char(109),char(95),char(109),char(97),char(120),char(86), -char(111),char(108),char(117),char(109),char(101),char(0),char(109),char(95),char(116),char(105),char(109),char(101),char(83),char(99),char(97),char(108),char(101),char(0),char(109),char(95), -char(118),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(73),char(116),char(101),char(114),char(97),char(116),char(105),char(111),char(110),char(115),char(0),char(109), -char(95),char(112),char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(73),char(116),char(101),char(114),char(97),char(116),char(105),char(111),char(110),char(115),char(0), -char(109),char(95),char(100),char(114),char(105),char(102),char(116),char(73),char(116),char(101),char(114),char(97),char(116),char(105),char(111),char(110),char(115),char(0),char(109),char(95), -char(99),char(108),char(117),char(115),char(116),char(101),char(114),char(73),char(116),char(101),char(114),char(97),char(116),char(105),char(111),char(110),char(115),char(0),char(109),char(95), -char(114),char(111),char(116),char(0),char(109),char(95),char(115),char(99),char(97),char(108),char(101),char(0),char(109),char(95),char(97),char(113),char(113),char(0),char(109),char(95), -char(99),char(111),char(109),char(0),char(42),char(109),char(95),char(112),char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(115),char(0),char(42),char(109),char(95), -char(119),char(101),char(105),char(103),char(104),char(116),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(80),char(111),char(115),char(105),char(116),char(105),char(111), -char(110),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(87),char(101),char(105),char(103),char(116),char(115),char(0),char(109),char(95),char(98),char(118),char(111), -char(108),char(117),char(109),char(101),char(0),char(109),char(95),char(98),char(102),char(114),char(97),char(109),char(101),char(0),char(109),char(95),char(102),char(114),char(97),char(109), -char(101),char(120),char(102),char(111),char(114),char(109),char(0),char(109),char(95),char(108),char(111),char(99),char(105),char(105),char(0),char(109),char(95),char(105),char(110),char(118), -char(119),char(105),char(0),char(109),char(95),char(118),char(105),char(109),char(112),char(117),char(108),char(115),char(101),char(115),char(91),char(50),char(93),char(0),char(109),char(95), -char(100),char(105),char(109),char(112),char(117),char(108),char(115),char(101),char(115),char(91),char(50),char(93),char(0),char(109),char(95),char(108),char(118),char(0),char(109),char(95), -char(97),char(118),char(0),char(42),char(109),char(95),char(102),char(114),char(97),char(109),char(101),char(114),char(101),char(102),char(115),char(0),char(42),char(109),char(95),char(110), -char(111),char(100),char(101),char(73),char(110),char(100),char(105),char(99),char(101),char(115),char(0),char(42),char(109),char(95),char(109),char(97),char(115),char(115),char(101),char(115), -char(0),char(109),char(95),char(110),char(117),char(109),char(70),char(114),char(97),char(109),char(101),char(82),char(101),char(102),char(115),char(0),char(109),char(95),char(110),char(117), -char(109),char(78),char(111),char(100),char(101),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(77),char(97),char(115),char(115),char(101),char(115),char(0),char(109), -char(95),char(105),char(100),char(109),char(97),char(115),char(115),char(0),char(109),char(95),char(105),char(109),char(97),char(115),char(115),char(0),char(109),char(95),char(110),char(118), -char(105),char(109),char(112),char(117),char(108),char(115),char(101),char(115),char(0),char(109),char(95),char(110),char(100),char(105),char(109),char(112),char(117),char(108),char(115),char(101), -char(115),char(0),char(109),char(95),char(110),char(100),char(97),char(109),char(112),char(105),char(110),char(103),char(0),char(109),char(95),char(108),char(100),char(97),char(109),char(112), -char(105),char(110),char(103),char(0),char(109),char(95),char(97),char(100),char(97),char(109),char(112),char(105),char(110),char(103),char(0),char(109),char(95),char(109),char(97),char(116), -char(99),char(104),char(105),char(110),char(103),char(0),char(109),char(95),char(109),char(97),char(120),char(83),char(101),char(108),char(102),char(67),char(111),char(108),char(108),char(105), -char(115),char(105),char(111),char(110),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(0),char(109),char(95),char(115),char(101),char(108),char(102),char(67),char(111), -char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(70),char(97),char(99),char(116),char(111),char(114), -char(0),char(109),char(95),char(99),char(111),char(110),char(116),char(97),char(105),char(110),char(115),char(65),char(110),char(99),char(104),char(111),char(114),char(0),char(109),char(95), -char(99),char(111),char(108),char(108),char(105),char(100),char(101),char(0),char(109),char(95),char(99),char(108),char(117),char(115),char(116),char(101),char(114),char(73),char(110),char(100), -char(101),char(120),char(0),char(42),char(109),char(95),char(98),char(111),char(100),char(121),char(65),char(0),char(42),char(109),char(95),char(98),char(111),char(100),char(121),char(66), -char(0),char(109),char(95),char(114),char(101),char(102),char(115),char(91),char(50),char(93),char(0),char(109),char(95),char(99),char(102),char(109),char(0),char(109),char(95),char(115), -char(112),char(108),char(105),char(116),char(0),char(109),char(95),char(100),char(101),char(108),char(101),char(116),char(101),char(0),char(109),char(95),char(114),char(101),char(108),char(80), -char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(91),char(50),char(93),char(0),char(109),char(95),char(98),char(111),char(100),char(121),char(65),char(116),char(121), -char(112),char(101),char(0),char(109),char(95),char(98),char(111),char(100),char(121),char(66),char(116),char(121),char(112),char(101),char(0),char(109),char(95),char(106),char(111),char(105), -char(110),char(116),char(84),char(121),char(112),char(101),char(0),char(42),char(109),char(95),char(112),char(111),char(115),char(101),char(0),char(42),char(42),char(109),char(95),char(109), -char(97),char(116),char(101),char(114),char(105),char(97),char(108),char(115),char(0),char(42),char(109),char(95),char(110),char(111),char(100),char(101),char(115),char(0),char(42),char(109), -char(95),char(108),char(105),char(110),char(107),char(115),char(0),char(42),char(109),char(95),char(102),char(97),char(99),char(101),char(115),char(0),char(42),char(109),char(95),char(116), -char(101),char(116),char(114),char(97),char(104),char(101),char(100),char(114),char(97),char(0),char(42),char(109),char(95),char(97),char(110),char(99),char(104),char(111),char(114),char(115), -char(0),char(42),char(109),char(95),char(99),char(108),char(117),char(115),char(116),char(101),char(114),char(115),char(0),char(42),char(109),char(95),char(106),char(111),char(105),char(110), -char(116),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(77),char(97),char(116),char(101),char(114),char(105),char(97),char(108),char(115),char(0),char(109),char(95), -char(110),char(117),char(109),char(76),char(105),char(110),char(107),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(70),char(97),char(99),char(101),char(115),char(0), -char(109),char(95),char(110),char(117),char(109),char(84),char(101),char(116),char(114),char(97),char(104),char(101),char(100),char(114),char(97),char(0),char(109),char(95),char(110),char(117), -char(109),char(65),char(110),char(99),char(104),char(111),char(114),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(67),char(108),char(117),char(115),char(116),char(101), -char(114),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(74),char(111),char(105),char(110),char(116),char(115),char(0),char(109),char(95),char(99),char(111),char(110), -char(102),char(105),char(103),char(0),char(109),char(95),char(122),char(101),char(114),char(111),char(82),char(111),char(116),char(80),char(97),char(114),char(101),char(110),char(116),char(84), -char(111),char(84),char(104),char(105),char(115),char(0),char(109),char(95),char(112),char(97),char(114),char(101),char(110),char(116),char(67),char(111),char(109),char(84),char(111),char(84), -char(104),char(105),char(115),char(80),char(105),char(118),char(111),char(116),char(79),char(102),char(102),char(115),char(101),char(116),char(0),char(109),char(95),char(116),char(104),char(105), -char(115),char(80),char(105),char(118),char(111),char(116),char(84),char(111),char(84),char(104),char(105),char(115),char(67),char(111),char(109),char(79),char(102),char(102),char(115),char(101), -char(116),char(0),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(65),char(120),char(105),char(115),char(84),char(111),char(112),char(91),char(54),char(93),char(0), -char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(65),char(120),char(105),char(115),char(66),char(111),char(116),char(116),char(111),char(109),char(91),char(54),char(93), -char(0),char(109),char(95),char(108),char(105),char(110),char(107),char(73),char(110),char(101),char(114),char(116),char(105),char(97),char(0),char(109),char(95),char(97),char(98),char(115), -char(70),char(114),char(97),char(109),char(101),char(84),char(111),char(116),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(84),char(111),char(112),char(0), -char(109),char(95),char(97),char(98),char(115),char(70),char(114),char(97),char(109),char(101),char(84),char(111),char(116),char(86),char(101),char(108),char(111),char(99),char(105),char(116), -char(121),char(66),char(111),char(116),char(116),char(111),char(109),char(0),char(109),char(95),char(97),char(98),char(115),char(70),char(114),char(97),char(109),char(101),char(76),char(111), -char(99),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(84),char(111),char(112),char(0),char(109),char(95),char(97),char(98),char(115),char(70),char(114), -char(97),char(109),char(101),char(76),char(111),char(99),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(66),char(111),char(116),char(116),char(111),char(109), -char(0),char(109),char(95),char(108),char(105),char(110),char(107),char(77),char(97),char(115),char(115),char(0),char(109),char(95),char(112),char(97),char(114),char(101),char(110),char(116), -char(73),char(110),char(100),char(101),char(120),char(0),char(109),char(95),char(100),char(111),char(102),char(67),char(111),char(117),char(110),char(116),char(0),char(109),char(95),char(112), -char(111),char(115),char(86),char(97),char(114),char(67),char(111),char(117),char(110),char(116),char(0),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(80),char(111), -char(115),char(91),char(55),char(93),char(0),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(86),char(101),char(108),char(91),char(54),char(93),char(0),char(109), -char(95),char(106),char(111),char(105),char(110),char(116),char(84),char(111),char(114),char(113),char(117),char(101),char(91),char(54),char(93),char(0),char(109),char(95),char(106),char(111), -char(105),char(110),char(116),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(0),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(70),char(114), -char(105),char(99),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(76),char(111),char(119),char(101),char(114),char(76), -char(105),char(109),char(105),char(116),char(0),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(85),char(112),char(112),char(101),char(114),char(76),char(105),char(109), -char(105),char(116),char(0),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(77),char(97),char(120),char(70),char(111),char(114),char(99),char(101),char(0),char(109), -char(95),char(106),char(111),char(105),char(110),char(116),char(77),char(97),char(120),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(42),char(109), -char(95),char(108),char(105),char(110),char(107),char(78),char(97),char(109),char(101),char(0),char(42),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(78),char(97), -char(109),char(101),char(0),char(42),char(109),char(95),char(108),char(105),char(110),char(107),char(67),char(111),char(108),char(108),char(105),char(100),char(101),char(114),char(0),char(42), -char(109),char(95),char(112),char(97),char(100),char(100),char(105),char(110),char(103),char(80),char(116),char(114),char(0),char(109),char(95),char(98),char(97),char(115),char(101),char(87), -char(111),char(114),char(108),char(100),char(80),char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(98),char(97),char(115),char(101),char(87), -char(111),char(114),char(108),char(100),char(79),char(114),char(105),char(101),char(110),char(116),char(97),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(98),char(97), -char(115),char(101),char(76),char(105),char(110),char(101),char(97),char(114),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109),char(95),char(98), -char(97),char(115),char(101),char(65),char(110),char(103),char(117),char(108),char(97),char(114),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109), -char(95),char(98),char(97),char(115),char(101),char(73),char(110),char(101),char(114),char(116),char(105),char(97),char(0),char(109),char(95),char(98),char(97),char(115),char(101),char(77), -char(97),char(115),char(115),char(0),char(42),char(109),char(95),char(98),char(97),char(115),char(101),char(78),char(97),char(109),char(101),char(0),char(42),char(109),char(95),char(98), -char(97),char(115),char(101),char(67),char(111),char(108),char(108),char(105),char(100),char(101),char(114),char(0),char(109),char(95),char(99),char(111),char(108),char(79),char(98),char(106), -char(68),char(97),char(116),char(97),char(0),char(42),char(109),char(95),char(109),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(0),char(109),char(95), -char(108),char(105),char(110),char(107),char(0),char(0),char(0),char(0),char(84),char(89),char(80),char(69),char(99),char(0),char(0),char(0),char(99),char(104),char(97),char(114), -char(0),char(117),char(99),char(104),char(97),char(114),char(0),char(115),char(104),char(111),char(114),char(116),char(0),char(117),char(115),char(104),char(111),char(114),char(116),char(0), -char(105),char(110),char(116),char(0),char(108),char(111),char(110),char(103),char(0),char(117),char(108),char(111),char(110),char(103),char(0),char(102),char(108),char(111),char(97),char(116), -char(0),char(100),char(111),char(117),char(98),char(108),char(101),char(0),char(118),char(111),char(105),char(100),char(0),char(80),char(111),char(105),char(110),char(116),char(101),char(114), -char(65),char(114),char(114),char(97),char(121),char(0),char(98),char(116),char(80),char(104),char(121),char(115),char(105),char(99),char(115),char(83),char(121),char(115),char(116),char(101), -char(109),char(0),char(76),char(105),char(115),char(116),char(66),char(97),char(115),char(101),char(0),char(98),char(116),char(86),char(101),char(99),char(116),char(111),char(114),char(51), -char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(86),char(101),char(99),char(116),char(111),char(114),char(51),char(68), -char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(116),char(101),char(114),char(110),char(105), -char(111),char(110),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(116),char(101),char(114), -char(110),char(105),char(111),char(110),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(97),char(116), -char(114),char(105),char(120),char(51),char(120),char(51),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(97), -char(116),char(114),char(105),char(120),char(51),char(120),char(51),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116), -char(84),char(114),char(97),char(110),char(115),char(102),char(111),char(114),char(109),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98), -char(116),char(84),char(114),char(97),char(110),char(115),char(102),char(111),char(114),char(109),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97), -char(0),char(98),char(116),char(66),char(118),char(104),char(83),char(117),char(98),char(116),char(114),char(101),char(101),char(73),char(110),char(102),char(111),char(68),char(97),char(116), +char(109),char(75),char(101),char(121),char(115),char(0),char(109),char(95),char(103),char(105),char(109),char(112),char(97),char(99),char(116),char(83),char(117),char(98),char(84),char(121), +char(112),char(101),char(0),char(42),char(109),char(95),char(117),char(110),char(115),char(99),char(97),char(108),char(101),char(100),char(80),char(111),char(105),char(110),char(116),char(115), +char(70),char(108),char(111),char(97),char(116),char(80),char(116),char(114),char(0),char(42),char(109),char(95),char(117),char(110),char(115),char(99),char(97),char(108),char(101),char(100), +char(80),char(111),char(105),char(110),char(116),char(115),char(68),char(111),char(117),char(98),char(108),char(101),char(80),char(116),char(114),char(0),char(109),char(95),char(110),char(117), +char(109),char(85),char(110),char(115),char(99),char(97),char(108),char(101),char(100),char(80),char(111),char(105),char(110),char(116),char(115),char(0),char(109),char(95),char(112),char(97), +char(100),char(100),char(105),char(110),char(103),char(51),char(91),char(52),char(93),char(0),char(42),char(109),char(95),char(98),char(114),char(111),char(97),char(100),char(112),char(104), +char(97),char(115),char(101),char(72),char(97),char(110),char(100),char(108),char(101),char(0),char(42),char(109),char(95),char(99),char(111),char(108),char(108),char(105),char(115),char(105), +char(111),char(110),char(83),char(104),char(97),char(112),char(101),char(0),char(42),char(109),char(95),char(114),char(111),char(111),char(116),char(67),char(111),char(108),char(108),char(105), +char(115),char(105),char(111),char(110),char(83),char(104),char(97),char(112),char(101),char(0),char(109),char(95),char(119),char(111),char(114),char(108),char(100),char(84),char(114),char(97), +char(110),char(115),char(102),char(111),char(114),char(109),char(0),char(109),char(95),char(105),char(110),char(116),char(101),char(114),char(112),char(111),char(108),char(97),char(116),char(105), +char(111),char(110),char(87),char(111),char(114),char(108),char(100),char(84),char(114),char(97),char(110),char(115),char(102),char(111),char(114),char(109),char(0),char(109),char(95),char(105), +char(110),char(116),char(101),char(114),char(112),char(111),char(108),char(97),char(116),char(105),char(111),char(110),char(76),char(105),char(110),char(101),char(97),char(114),char(86),char(101), +char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109),char(95),char(105),char(110),char(116),char(101),char(114),char(112),char(111),char(108),char(97),char(116),char(105), +char(111),char(110),char(65),char(110),char(103),char(117),char(108),char(97),char(114),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109),char(95), +char(97),char(110),char(105),char(115),char(111),char(116),char(114),char(111),char(112),char(105),char(99),char(70),char(114),char(105),char(99),char(116),char(105),char(111),char(110),char(0), +char(109),char(95),char(99),char(111),char(110),char(116),char(97),char(99),char(116),char(80),char(114),char(111),char(99),char(101),char(115),char(115),char(105),char(110),char(103),char(84), +char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(0),char(109),char(95),char(100),char(101),char(97),char(99),char(116),char(105),char(118),char(97),char(116), +char(105),char(111),char(110),char(84),char(105),char(109),char(101),char(0),char(109),char(95),char(102),char(114),char(105),char(99),char(116),char(105),char(111),char(110),char(0),char(109), +char(95),char(114),char(111),char(108),char(108),char(105),char(110),char(103),char(70),char(114),char(105),char(99),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(99), +char(111),char(110),char(116),char(97),char(99),char(116),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(0),char(109),char(95),char(99),char(111),char(110),char(116), +char(97),char(99),char(116),char(83),char(116),char(105),char(102),char(102),char(110),char(101),char(115),char(115),char(0),char(109),char(95),char(114),char(101),char(115),char(116),char(105), +char(116),char(117),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(104),char(105),char(116),char(70),char(114),char(97),char(99),char(116),char(105),char(111),char(110), +char(0),char(109),char(95),char(99),char(99),char(100),char(83),char(119),char(101),char(112),char(116),char(83),char(112),char(104),char(101),char(114),char(101),char(82),char(97),char(100), +char(105),char(117),char(115),char(0),char(109),char(95),char(99),char(99),char(100),char(77),char(111),char(116),char(105),char(111),char(110),char(84),char(104),char(114),char(101),char(115), +char(104),char(111),char(108),char(100),char(0),char(109),char(95),char(104),char(97),char(115),char(65),char(110),char(105),char(115),char(111),char(116),char(114),char(111),char(112),char(105), +char(99),char(70),char(114),char(105),char(99),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(99),char(111),char(108),char(108),char(105),char(115),char(105),char(111), +char(110),char(70),char(108),char(97),char(103),char(115),char(0),char(109),char(95),char(105),char(115),char(108),char(97),char(110),char(100),char(84),char(97),char(103),char(49),char(0), +char(109),char(95),char(99),char(111),char(109),char(112),char(97),char(110),char(105),char(111),char(110),char(73),char(100),char(0),char(109),char(95),char(97),char(99),char(116),char(105), +char(118),char(97),char(116),char(105),char(111),char(110),char(83),char(116),char(97),char(116),char(101),char(49),char(0),char(109),char(95),char(105),char(110),char(116),char(101),char(114), +char(110),char(97),char(108),char(84),char(121),char(112),char(101),char(0),char(109),char(95),char(99),char(104),char(101),char(99),char(107),char(67),char(111),char(108),char(108),char(105), +char(100),char(101),char(87),char(105),char(116),char(104),char(0),char(109),char(95),char(116),char(97),char(117),char(0),char(109),char(95),char(100),char(97),char(109),char(112),char(105), +char(110),char(103),char(0),char(109),char(95),char(116),char(105),char(109),char(101),char(83),char(116),char(101),char(112),char(0),char(109),char(95),char(109),char(97),char(120),char(69), +char(114),char(114),char(111),char(114),char(82),char(101),char(100),char(117),char(99),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(115),char(111),char(114),char(0), +char(109),char(95),char(101),char(114),char(112),char(0),char(109),char(95),char(101),char(114),char(112),char(50),char(0),char(109),char(95),char(103),char(108),char(111),char(98),char(97), +char(108),char(67),char(102),char(109),char(0),char(109),char(95),char(115),char(112),char(108),char(105),char(116),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(80), +char(101),char(110),char(101),char(116),char(114),char(97),char(116),char(105),char(111),char(110),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(0), +char(109),char(95),char(115),char(112),char(108),char(105),char(116),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(84),char(117),char(114),char(110),char(69),char(114), +char(112),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(83),char(108),char(111),char(112),char(0),char(109),char(95),char(119),char(97),char(114), +char(109),char(115),char(116),char(97),char(114),char(116),char(105),char(110),char(103),char(70),char(97),char(99),char(116),char(111),char(114),char(0),char(109),char(95),char(109),char(97), +char(120),char(71),char(121),char(114),char(111),char(115),char(99),char(111),char(112),char(105),char(99),char(70),char(111),char(114),char(99),char(101),char(0),char(109),char(95),char(115), +char(105),char(110),char(103),char(108),char(101),char(65),char(120),char(105),char(115),char(82),char(111),char(108),char(108),char(105),char(110),char(103),char(70),char(114),char(105),char(99), +char(116),char(105),char(111),char(110),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(0),char(109),char(95),char(110),char(117),char(109),char(73), +char(116),char(101),char(114),char(97),char(116),char(105),char(111),char(110),char(115),char(0),char(109),char(95),char(115),char(111),char(108),char(118),char(101),char(114),char(77),char(111), +char(100),char(101),char(0),char(109),char(95),char(114),char(101),char(115),char(116),char(105),char(110),char(103),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(82), +char(101),char(115),char(116),char(105),char(116),char(117),char(116),char(105),char(111),char(110),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(0), +char(109),char(95),char(109),char(105),char(110),char(105),char(109),char(117),char(109),char(83),char(111),char(108),char(118),char(101),char(114),char(66),char(97),char(116),char(99),char(104), +char(83),char(105),char(122),char(101),char(0),char(109),char(95),char(115),char(112),char(108),char(105),char(116),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(0), +char(109),char(95),char(115),char(111),char(108),char(118),char(101),char(114),char(73),char(110),char(102),char(111),char(0),char(109),char(95),char(103),char(114),char(97),char(118),char(105), +char(116),char(121),char(0),char(109),char(95),char(99),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(79),char(98),char(106),char(101),char(99),char(116), +char(68),char(97),char(116),char(97),char(0),char(109),char(95),char(105),char(110),char(118),char(73),char(110),char(101),char(114),char(116),char(105),char(97),char(84),char(101),char(110), +char(115),char(111),char(114),char(87),char(111),char(114),char(108),char(100),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(86),char(101),char(108), +char(111),char(99),char(105),char(116),char(121),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(86),char(101),char(108),char(111),char(99), +char(105),char(116),char(121),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(70),char(97),char(99),char(116),char(111),char(114),char(0), +char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(70),char(97),char(99),char(116),char(111),char(114),char(0),char(109),char(95),char(103),char(114),char(97), +char(118),char(105),char(116),char(121),char(95),char(97),char(99),char(99),char(101),char(108),char(101),char(114),char(97),char(116),char(105),char(111),char(110),char(0),char(109),char(95), +char(105),char(110),char(118),char(73),char(110),char(101),char(114),char(116),char(105),char(97),char(76),char(111),char(99),char(97),char(108),char(0),char(109),char(95),char(116),char(111), +char(116),char(97),char(108),char(70),char(111),char(114),char(99),char(101),char(0),char(109),char(95),char(116),char(111),char(116),char(97),char(108),char(84),char(111),char(114),char(113), +char(117),char(101),char(0),char(109),char(95),char(105),char(110),char(118),char(101),char(114),char(115),char(101),char(77),char(97),char(115),char(115),char(0),char(109),char(95),char(108), +char(105),char(110),char(101),char(97),char(114),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108), +char(97),char(114),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(0),char(109),char(95),char(97),char(100),char(100),char(105),char(116),char(105),char(111),char(110), +char(97),char(108),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(70),char(97),char(99),char(116),char(111),char(114),char(0),char(109),char(95),char(97),char(100), +char(100),char(105),char(116),char(105),char(111),char(110),char(97),char(108),char(76),char(105),char(110),char(101),char(97),char(114),char(68),char(97),char(109),char(112),char(105),char(110), +char(103),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(83),char(113),char(114),char(0),char(109),char(95),char(97),char(100),char(100),char(105), +char(116),char(105),char(111),char(110),char(97),char(108),char(65),char(110),char(103),char(117),char(108),char(97),char(114),char(68),char(97),char(109),char(112),char(105),char(110),char(103), +char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(83),char(113),char(114),char(0),char(109),char(95),char(97),char(100),char(100),char(105),char(116), +char(105),char(111),char(110),char(97),char(108),char(65),char(110),char(103),char(117),char(108),char(97),char(114),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(70), +char(97),char(99),char(116),char(111),char(114),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(83),char(108),char(101),char(101),char(112),char(105), +char(110),char(103),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97), +char(114),char(83),char(108),char(101),char(101),char(112),char(105),char(110),char(103),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(0),char(109), +char(95),char(97),char(100),char(100),char(105),char(116),char(105),char(111),char(110),char(97),char(108),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(0),char(109), +char(95),char(110),char(117),char(109),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(82),char(111),char(119),char(115),char(0),char(110), +char(117),char(98),char(0),char(42),char(109),char(95),char(114),char(98),char(65),char(0),char(42),char(109),char(95),char(114),char(98),char(66),char(0),char(109),char(95),char(111), +char(98),char(106),char(101),char(99),char(116),char(84),char(121),char(112),char(101),char(0),char(109),char(95),char(117),char(115),char(101),char(114),char(67),char(111),char(110),char(115), +char(116),char(114),char(97),char(105),char(110),char(116),char(84),char(121),char(112),char(101),char(0),char(109),char(95),char(117),char(115),char(101),char(114),char(67),char(111),char(110), +char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(73),char(100),char(0),char(109),char(95),char(110),char(101),char(101),char(100),char(115),char(70),char(101),char(101), +char(100),char(98),char(97),char(99),char(107),char(0),char(109),char(95),char(97),char(112),char(112),char(108),char(105),char(101),char(100),char(73),char(109),char(112),char(117),char(108), +char(115),char(101),char(0),char(109),char(95),char(100),char(98),char(103),char(68),char(114),char(97),char(119),char(83),char(105),char(122),char(101),char(0),char(109),char(95),char(100), +char(105),char(115),char(97),char(98),char(108),char(101),char(67),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(115),char(66),char(101),char(116),char(119), +char(101),char(101),char(110),char(76),char(105),char(110),char(107),char(101),char(100),char(66),char(111),char(100),char(105),char(101),char(115),char(0),char(109),char(95),char(111),char(118), +char(101),char(114),char(114),char(105),char(100),char(101),char(78),char(117),char(109),char(83),char(111),char(108),char(118),char(101),char(114),char(73),char(116),char(101),char(114),char(97), +char(116),char(105),char(111),char(110),char(115),char(0),char(109),char(95),char(98),char(114),char(101),char(97),char(107),char(105),char(110),char(103),char(73),char(109),char(112),char(117), +char(108),char(115),char(101),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(0),char(109),char(95),char(105),char(115),char(69),char(110),char(97), +char(98),char(108),char(101),char(100),char(0),char(112),char(97),char(100),char(100),char(105),char(110),char(103),char(91),char(52),char(93),char(0),char(109),char(95),char(116),char(121), +char(112),char(101),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(109),char(95),char(112), +char(105),char(118),char(111),char(116),char(73),char(110),char(65),char(0),char(109),char(95),char(112),char(105),char(118),char(111),char(116),char(73),char(110),char(66),char(0),char(109), +char(95),char(114),char(98),char(65),char(70),char(114),char(97),char(109),char(101),char(0),char(109),char(95),char(114),char(98),char(66),char(70),char(114),char(97),char(109),char(101), +char(0),char(109),char(95),char(117),char(115),char(101),char(82),char(101),char(102),char(101),char(114),char(101),char(110),char(99),char(101),char(70),char(114),char(97),char(109),char(101), +char(65),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(79),char(110),char(108),char(121),char(0),char(109),char(95),char(101),char(110), +char(97),char(98),char(108),char(101),char(65),char(110),char(103),char(117),char(108),char(97),char(114),char(77),char(111),char(116),char(111),char(114),char(0),char(109),char(95),char(109), +char(111),char(116),char(111),char(114),char(84),char(97),char(114),char(103),char(101),char(116),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109), +char(95),char(109),char(97),char(120),char(77),char(111),char(116),char(111),char(114),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(0),char(109),char(95),char(108), +char(111),char(119),char(101),char(114),char(76),char(105),char(109),char(105),char(116),char(0),char(109),char(95),char(117),char(112),char(112),char(101),char(114),char(76),char(105),char(109), +char(105),char(116),char(0),char(109),char(95),char(108),char(105),char(109),char(105),char(116),char(83),char(111),char(102),char(116),char(110),char(101),char(115),char(115),char(0),char(109), +char(95),char(98),char(105),char(97),char(115),char(70),char(97),char(99),char(116),char(111),char(114),char(0),char(109),char(95),char(114),char(101),char(108),char(97),char(120),char(97), +char(116),char(105),char(111),char(110),char(70),char(97),char(99),char(116),char(111),char(114),char(0),char(109),char(95),char(112),char(97),char(100),char(100),char(105),char(110),char(103), +char(49),char(91),char(52),char(93),char(0),char(109),char(95),char(115),char(119),char(105),char(110),char(103),char(83),char(112),char(97),char(110),char(49),char(0),char(109),char(95), +char(115),char(119),char(105),char(110),char(103),char(83),char(112),char(97),char(110),char(50),char(0),char(109),char(95),char(116),char(119),char(105),char(115),char(116),char(83),char(112), +char(97),char(110),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(85),char(112),char(112),char(101),char(114),char(76),char(105),char(109),char(105), +char(116),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(76),char(111),char(119),char(101),char(114),char(76),char(105),char(109),char(105),char(116), +char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(85),char(112),char(112),char(101),char(114),char(76),char(105),char(109),char(105),char(116), +char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(76),char(111),char(119),char(101),char(114),char(76),char(105),char(109),char(105),char(116), +char(0),char(109),char(95),char(117),char(115),char(101),char(76),char(105),char(110),char(101),char(97),char(114),char(82),char(101),char(102),char(101),char(114),char(101),char(110),char(99), +char(101),char(70),char(114),char(97),char(109),char(101),char(65),char(0),char(109),char(95),char(117),char(115),char(101),char(79),char(102),char(102),char(115),char(101),char(116),char(70), +char(111),char(114),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(114),char(97),char(109),char(101),char(0),char(109),char(95), +char(54),char(100),char(111),char(102),char(68),char(97),char(116),char(97),char(0),char(109),char(95),char(115),char(112),char(114),char(105),char(110),char(103),char(69),char(110),char(97), +char(98),char(108),char(101),char(100),char(91),char(54),char(93),char(0),char(109),char(95),char(101),char(113),char(117),char(105),char(108),char(105),char(98),char(114),char(105),char(117), +char(109),char(80),char(111),char(105),char(110),char(116),char(91),char(54),char(93),char(0),char(109),char(95),char(115),char(112),char(114),char(105),char(110),char(103),char(83),char(116), +char(105),char(102),char(102),char(110),char(101),char(115),char(115),char(91),char(54),char(93),char(0),char(109),char(95),char(115),char(112),char(114),char(105),char(110),char(103),char(68), +char(97),char(109),char(112),char(105),char(110),char(103),char(91),char(54),char(93),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(66),char(111), +char(117),char(110),char(99),char(101),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(83),char(116),char(111),char(112),char(69),char(82),char(80), +char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(83),char(116),char(111),char(112),char(67),char(70),char(77),char(0),char(109),char(95),char(108), +char(105),char(110),char(101),char(97),char(114),char(77),char(111),char(116),char(111),char(114),char(69),char(82),char(80),char(0),char(109),char(95),char(108),char(105),char(110),char(101), +char(97),char(114),char(77),char(111),char(116),char(111),char(114),char(67),char(70),char(77),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(84), +char(97),char(114),char(103),char(101),char(116),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109),char(95),char(108),char(105),char(110),char(101), +char(97),char(114),char(77),char(97),char(120),char(77),char(111),char(116),char(111),char(114),char(70),char(111),char(114),char(99),char(101),char(0),char(109),char(95),char(108),char(105), +char(110),char(101),char(97),char(114),char(83),char(101),char(114),char(118),char(111),char(84),char(97),char(114),char(103),char(101),char(116),char(0),char(109),char(95),char(108),char(105), +char(110),char(101),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(83),char(116),char(105),char(102),char(102),char(110),char(101),char(115),char(115),char(0), +char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(68),char(97),char(109),char(112),char(105),char(110), +char(103),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(69),char(113),char(117),char(105),char(108),char(105),char(98),char(114),char(105),char(117), +char(109),char(80),char(111),char(105),char(110),char(116),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(69),char(110),char(97),char(98),char(108), +char(101),char(77),char(111),char(116),char(111),char(114),char(91),char(52),char(93),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(83),char(101), +char(114),char(118),char(111),char(77),char(111),char(116),char(111),char(114),char(91),char(52),char(93),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114), +char(69),char(110),char(97),char(98),char(108),char(101),char(83),char(112),char(114),char(105),char(110),char(103),char(91),char(52),char(93),char(0),char(109),char(95),char(108),char(105), +char(110),char(101),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(83),char(116),char(105),char(102),char(102),char(110),char(101),char(115),char(115),char(76), +char(105),char(109),char(105),char(116),char(101),char(100),char(91),char(52),char(93),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(83),char(112), +char(114),char(105),char(110),char(103),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(76),char(105),char(109),char(105),char(116),char(101),char(100),char(91),char(52), +char(93),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(66),char(111),char(117),char(110),char(99),char(101),char(0),char(109),char(95), +char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(83),char(116),char(111),char(112),char(69),char(82),char(80),char(0),char(109),char(95),char(97),char(110),char(103), +char(117),char(108),char(97),char(114),char(83),char(116),char(111),char(112),char(67),char(70),char(77),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97), +char(114),char(77),char(111),char(116),char(111),char(114),char(69),char(82),char(80),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(77), +char(111),char(116),char(111),char(114),char(67),char(70),char(77),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(84),char(97),char(114), +char(103),char(101),char(116),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97), +char(114),char(77),char(97),char(120),char(77),char(111),char(116),char(111),char(114),char(70),char(111),char(114),char(99),char(101),char(0),char(109),char(95),char(97),char(110),char(103), +char(117),char(108),char(97),char(114),char(83),char(101),char(114),char(118),char(111),char(84),char(97),char(114),char(103),char(101),char(116),char(0),char(109),char(95),char(97),char(110), +char(103),char(117),char(108),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(83),char(116),char(105),char(102),char(102),char(110),char(101),char(115),char(115), +char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(68),char(97),char(109),char(112), +char(105),char(110),char(103),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(69),char(113),char(117),char(105),char(108),char(105),char(98), +char(114),char(105),char(117),char(109),char(80),char(111),char(105),char(110),char(116),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(69), +char(110),char(97),char(98),char(108),char(101),char(77),char(111),char(116),char(111),char(114),char(91),char(52),char(93),char(0),char(109),char(95),char(97),char(110),char(103),char(117), +char(108),char(97),char(114),char(83),char(101),char(114),char(118),char(111),char(77),char(111),char(116),char(111),char(114),char(91),char(52),char(93),char(0),char(109),char(95),char(97), +char(110),char(103),char(117),char(108),char(97),char(114),char(69),char(110),char(97),char(98),char(108),char(101),char(83),char(112),char(114),char(105),char(110),char(103),char(91),char(52), +char(93),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(83),char(116),char(105), +char(102),char(102),char(110),char(101),char(115),char(115),char(76),char(105),char(109),char(105),char(116),char(101),char(100),char(91),char(52),char(93),char(0),char(109),char(95),char(97), +char(110),char(103),char(117),char(108),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(76), +char(105),char(109),char(105),char(116),char(101),char(100),char(91),char(52),char(93),char(0),char(109),char(95),char(114),char(111),char(116),char(97),char(116),char(101),char(79),char(114), +char(100),char(101),char(114),char(0),char(109),char(95),char(97),char(120),char(105),char(115),char(73),char(110),char(65),char(0),char(109),char(95),char(97),char(120),char(105),char(115), +char(73),char(110),char(66),char(0),char(109),char(95),char(114),char(97),char(116),char(105),char(111),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114), +char(83),char(116),char(105),char(102),char(102),char(110),char(101),char(115),char(115),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(83), +char(116),char(105),char(102),char(102),char(110),char(101),char(115),char(115),char(0),char(109),char(95),char(118),char(111),char(108),char(117),char(109),char(101),char(83),char(116),char(105), +char(102),char(102),char(110),char(101),char(115),char(115),char(0),char(42),char(109),char(95),char(109),char(97),char(116),char(101),char(114),char(105),char(97),char(108),char(0),char(109), +char(95),char(112),char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(112),char(114),char(101),char(118),char(105),char(111),char(117),char(115), +char(80),char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(118),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0), +char(109),char(95),char(97),char(99),char(99),char(117),char(109),char(117),char(108),char(97),char(116),char(101),char(100),char(70),char(111),char(114),char(99),char(101),char(0),char(109), +char(95),char(110),char(111),char(114),char(109),char(97),char(108),char(0),char(109),char(95),char(97),char(114),char(101),char(97),char(0),char(109),char(95),char(97),char(116),char(116), +char(97),char(99),char(104),char(0),char(109),char(95),char(110),char(111),char(100),char(101),char(73),char(110),char(100),char(105),char(99),char(101),char(115),char(91),char(50),char(93), +char(0),char(109),char(95),char(114),char(101),char(115),char(116),char(76),char(101),char(110),char(103),char(116),char(104),char(0),char(109),char(95),char(98),char(98),char(101),char(110), +char(100),char(105),char(110),char(103),char(0),char(109),char(95),char(110),char(111),char(100),char(101),char(73),char(110),char(100),char(105),char(99),char(101),char(115),char(91),char(51), +char(93),char(0),char(109),char(95),char(114),char(101),char(115),char(116),char(65),char(114),char(101),char(97),char(0),char(109),char(95),char(99),char(48),char(91),char(52),char(93), +char(0),char(109),char(95),char(110),char(111),char(100),char(101),char(73),char(110),char(100),char(105),char(99),char(101),char(115),char(91),char(52),char(93),char(0),char(109),char(95), +char(114),char(101),char(115),char(116),char(86),char(111),char(108),char(117),char(109),char(101),char(0),char(109),char(95),char(99),char(49),char(0),char(109),char(95),char(99),char(50), +char(0),char(109),char(95),char(99),char(48),char(0),char(109),char(95),char(108),char(111),char(99),char(97),char(108),char(70),char(114),char(97),char(109),char(101),char(0),char(42), +char(109),char(95),char(114),char(105),char(103),char(105),char(100),char(66),char(111),char(100),char(121),char(0),char(109),char(95),char(110),char(111),char(100),char(101),char(73),char(110), +char(100),char(101),char(120),char(0),char(109),char(95),char(97),char(101),char(114),char(111),char(77),char(111),char(100),char(101),char(108),char(0),char(109),char(95),char(98),char(97), +char(117),char(109),char(103),char(97),char(114),char(116),char(101),char(0),char(109),char(95),char(100),char(114),char(97),char(103),char(0),char(109),char(95),char(108),char(105),char(102), +char(116),char(0),char(109),char(95),char(112),char(114),char(101),char(115),char(115),char(117),char(114),char(101),char(0),char(109),char(95),char(118),char(111),char(108),char(117),char(109), +char(101),char(0),char(109),char(95),char(100),char(121),char(110),char(97),char(109),char(105),char(99),char(70),char(114),char(105),char(99),char(116),char(105),char(111),char(110),char(0), +char(109),char(95),char(112),char(111),char(115),char(101),char(77),char(97),char(116),char(99),char(104),char(0),char(109),char(95),char(114),char(105),char(103),char(105),char(100),char(67), +char(111),char(110),char(116),char(97),char(99),char(116),char(72),char(97),char(114),char(100),char(110),char(101),char(115),char(115),char(0),char(109),char(95),char(107),char(105),char(110), +char(101),char(116),char(105),char(99),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(72),char(97),char(114),char(100),char(110),char(101),char(115),char(115),char(0), +char(109),char(95),char(115),char(111),char(102),char(116),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(72),char(97),char(114),char(100),char(110),char(101),char(115), +char(115),char(0),char(109),char(95),char(97),char(110),char(99),char(104),char(111),char(114),char(72),char(97),char(114),char(100),char(110),char(101),char(115),char(115),char(0),char(109), +char(95),char(115),char(111),char(102),char(116),char(82),char(105),char(103),char(105),char(100),char(67),char(108),char(117),char(115),char(116),char(101),char(114),char(72),char(97),char(114), +char(100),char(110),char(101),char(115),char(115),char(0),char(109),char(95),char(115),char(111),char(102),char(116),char(75),char(105),char(110),char(101),char(116),char(105),char(99),char(67), +char(108),char(117),char(115),char(116),char(101),char(114),char(72),char(97),char(114),char(100),char(110),char(101),char(115),char(115),char(0),char(109),char(95),char(115),char(111),char(102), +char(116),char(83),char(111),char(102),char(116),char(67),char(108),char(117),char(115),char(116),char(101),char(114),char(72),char(97),char(114),char(100),char(110),char(101),char(115),char(115), +char(0),char(109),char(95),char(115),char(111),char(102),char(116),char(82),char(105),char(103),char(105),char(100),char(67),char(108),char(117),char(115),char(116),char(101),char(114),char(73), +char(109),char(112),char(117),char(108),char(115),char(101),char(83),char(112),char(108),char(105),char(116),char(0),char(109),char(95),char(115),char(111),char(102),char(116),char(75),char(105), +char(110),char(101),char(116),char(105),char(99),char(67),char(108),char(117),char(115),char(116),char(101),char(114),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(83), +char(112),char(108),char(105),char(116),char(0),char(109),char(95),char(115),char(111),char(102),char(116),char(83),char(111),char(102),char(116),char(67),char(108),char(117),char(115),char(116), +char(101),char(114),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(83),char(112),char(108),char(105),char(116),char(0),char(109),char(95),char(109),char(97),char(120), +char(86),char(111),char(108),char(117),char(109),char(101),char(0),char(109),char(95),char(116),char(105),char(109),char(101),char(83),char(99),char(97),char(108),char(101),char(0),char(109), +char(95),char(118),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(73),char(116),char(101),char(114),char(97),char(116),char(105),char(111),char(110),char(115),char(0), +char(109),char(95),char(112),char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(73),char(116),char(101),char(114),char(97),char(116),char(105),char(111),char(110),char(115), +char(0),char(109),char(95),char(100),char(114),char(105),char(102),char(116),char(73),char(116),char(101),char(114),char(97),char(116),char(105),char(111),char(110),char(115),char(0),char(109), +char(95),char(99),char(108),char(117),char(115),char(116),char(101),char(114),char(73),char(116),char(101),char(114),char(97),char(116),char(105),char(111),char(110),char(115),char(0),char(109), +char(95),char(114),char(111),char(116),char(0),char(109),char(95),char(115),char(99),char(97),char(108),char(101),char(0),char(109),char(95),char(97),char(113),char(113),char(0),char(109), +char(95),char(99),char(111),char(109),char(0),char(42),char(109),char(95),char(112),char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(115),char(0),char(42),char(109), +char(95),char(119),char(101),char(105),char(103),char(104),char(116),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(80),char(111),char(115),char(105),char(116),char(105), +char(111),char(110),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(87),char(101),char(105),char(103),char(116),char(115),char(0),char(109),char(95),char(98),char(118), +char(111),char(108),char(117),char(109),char(101),char(0),char(109),char(95),char(98),char(102),char(114),char(97),char(109),char(101),char(0),char(109),char(95),char(102),char(114),char(97), +char(109),char(101),char(120),char(102),char(111),char(114),char(109),char(0),char(109),char(95),char(108),char(111),char(99),char(105),char(105),char(0),char(109),char(95),char(105),char(110), +char(118),char(119),char(105),char(0),char(109),char(95),char(118),char(105),char(109),char(112),char(117),char(108),char(115),char(101),char(115),char(91),char(50),char(93),char(0),char(109), +char(95),char(100),char(105),char(109),char(112),char(117),char(108),char(115),char(101),char(115),char(91),char(50),char(93),char(0),char(109),char(95),char(108),char(118),char(0),char(109), +char(95),char(97),char(118),char(0),char(42),char(109),char(95),char(102),char(114),char(97),char(109),char(101),char(114),char(101),char(102),char(115),char(0),char(42),char(109),char(95), +char(110),char(111),char(100),char(101),char(73),char(110),char(100),char(105),char(99),char(101),char(115),char(0),char(42),char(109),char(95),char(109),char(97),char(115),char(115),char(101), +char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(70),char(114),char(97),char(109),char(101),char(82),char(101),char(102),char(115),char(0),char(109),char(95),char(110), +char(117),char(109),char(78),char(111),char(100),char(101),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(77),char(97),char(115),char(115),char(101),char(115),char(0), +char(109),char(95),char(105),char(100),char(109),char(97),char(115),char(115),char(0),char(109),char(95),char(105),char(109),char(97),char(115),char(115),char(0),char(109),char(95),char(110), +char(118),char(105),char(109),char(112),char(117),char(108),char(115),char(101),char(115),char(0),char(109),char(95),char(110),char(100),char(105),char(109),char(112),char(117),char(108),char(115), +char(101),char(115),char(0),char(109),char(95),char(110),char(100),char(97),char(109),char(112),char(105),char(110),char(103),char(0),char(109),char(95),char(108),char(100),char(97),char(109), +char(112),char(105),char(110),char(103),char(0),char(109),char(95),char(97),char(100),char(97),char(109),char(112),char(105),char(110),char(103),char(0),char(109),char(95),char(109),char(97), +char(116),char(99),char(104),char(105),char(110),char(103),char(0),char(109),char(95),char(109),char(97),char(120),char(83),char(101),char(108),char(102),char(67),char(111),char(108),char(108), +char(105),char(115),char(105),char(111),char(110),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(0),char(109),char(95),char(115),char(101),char(108),char(102),char(67), +char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(70),char(97),char(99),char(116),char(111), +char(114),char(0),char(109),char(95),char(99),char(111),char(110),char(116),char(97),char(105),char(110),char(115),char(65),char(110),char(99),char(104),char(111),char(114),char(0),char(109), +char(95),char(99),char(111),char(108),char(108),char(105),char(100),char(101),char(0),char(109),char(95),char(99),char(108),char(117),char(115),char(116),char(101),char(114),char(73),char(110), +char(100),char(101),char(120),char(0),char(42),char(109),char(95),char(98),char(111),char(100),char(121),char(65),char(0),char(42),char(109),char(95),char(98),char(111),char(100),char(121), +char(66),char(0),char(109),char(95),char(114),char(101),char(102),char(115),char(91),char(50),char(93),char(0),char(109),char(95),char(99),char(102),char(109),char(0),char(109),char(95), +char(115),char(112),char(108),char(105),char(116),char(0),char(109),char(95),char(100),char(101),char(108),char(101),char(116),char(101),char(0),char(109),char(95),char(114),char(101),char(108), +char(80),char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(91),char(50),char(93),char(0),char(109),char(95),char(98),char(111),char(100),char(121),char(65),char(116), +char(121),char(112),char(101),char(0),char(109),char(95),char(98),char(111),char(100),char(121),char(66),char(116),char(121),char(112),char(101),char(0),char(109),char(95),char(106),char(111), +char(105),char(110),char(116),char(84),char(121),char(112),char(101),char(0),char(42),char(109),char(95),char(112),char(111),char(115),char(101),char(0),char(42),char(42),char(109),char(95), +char(109),char(97),char(116),char(101),char(114),char(105),char(97),char(108),char(115),char(0),char(42),char(109),char(95),char(110),char(111),char(100),char(101),char(115),char(0),char(42), +char(109),char(95),char(108),char(105),char(110),char(107),char(115),char(0),char(42),char(109),char(95),char(102),char(97),char(99),char(101),char(115),char(0),char(42),char(109),char(95), +char(116),char(101),char(116),char(114),char(97),char(104),char(101),char(100),char(114),char(97),char(0),char(42),char(109),char(95),char(97),char(110),char(99),char(104),char(111),char(114), +char(115),char(0),char(42),char(109),char(95),char(99),char(108),char(117),char(115),char(116),char(101),char(114),char(115),char(0),char(42),char(109),char(95),char(106),char(111),char(105), +char(110),char(116),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(77),char(97),char(116),char(101),char(114),char(105),char(97),char(108),char(115),char(0),char(109), +char(95),char(110),char(117),char(109),char(76),char(105),char(110),char(107),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(70),char(97),char(99),char(101),char(115), +char(0),char(109),char(95),char(110),char(117),char(109),char(84),char(101),char(116),char(114),char(97),char(104),char(101),char(100),char(114),char(97),char(0),char(109),char(95),char(110), +char(117),char(109),char(65),char(110),char(99),char(104),char(111),char(114),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(67),char(108),char(117),char(115),char(116), +char(101),char(114),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(74),char(111),char(105),char(110),char(116),char(115),char(0),char(109),char(95),char(99),char(111), +char(110),char(102),char(105),char(103),char(0),char(109),char(95),char(122),char(101),char(114),char(111),char(82),char(111),char(116),char(80),char(97),char(114),char(101),char(110),char(116), +char(84),char(111),char(84),char(104),char(105),char(115),char(0),char(109),char(95),char(112),char(97),char(114),char(101),char(110),char(116),char(67),char(111),char(109),char(84),char(111), +char(84),char(104),char(105),char(115),char(67),char(111),char(109),char(79),char(102),char(102),char(115),char(101),char(116),char(0),char(109),char(95),char(116),char(104),char(105),char(115), +char(80),char(105),char(118),char(111),char(116),char(84),char(111),char(84),char(104),char(105),char(115),char(67),char(111),char(109),char(79),char(102),char(102),char(115),char(101),char(116), +char(0),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(65),char(120),char(105),char(115),char(84),char(111),char(112),char(91),char(54),char(93),char(0),char(109), +char(95),char(106),char(111),char(105),char(110),char(116),char(65),char(120),char(105),char(115),char(66),char(111),char(116),char(116),char(111),char(109),char(91),char(54),char(93),char(0), +char(109),char(95),char(108),char(105),char(110),char(107),char(73),char(110),char(101),char(114),char(116),char(105),char(97),char(0),char(109),char(95),char(108),char(105),char(110),char(107), +char(77),char(97),char(115),char(115),char(0),char(109),char(95),char(112),char(97),char(114),char(101),char(110),char(116),char(73),char(110),char(100),char(101),char(120),char(0),char(109), +char(95),char(100),char(111),char(102),char(67),char(111),char(117),char(110),char(116),char(0),char(109),char(95),char(112),char(111),char(115),char(86),char(97),char(114),char(67),char(111), +char(117),char(110),char(116),char(0),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(80),char(111),char(115),char(91),char(55),char(93),char(0),char(109),char(95), +char(106),char(111),char(105),char(110),char(116),char(86),char(101),char(108),char(91),char(54),char(93),char(0),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(84), +char(111),char(114),char(113),char(117),char(101),char(91),char(54),char(93),char(0),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(68),char(97),char(109),char(112), +char(105),char(110),char(103),char(0),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(70),char(114),char(105),char(99),char(116),char(105),char(111),char(110),char(0), +char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(76),char(111),char(119),char(101),char(114),char(76),char(105),char(109),char(105),char(116),char(0),char(109),char(95), +char(106),char(111),char(105),char(110),char(116),char(85),char(112),char(112),char(101),char(114),char(76),char(105),char(109),char(105),char(116),char(0),char(109),char(95),char(106),char(111), +char(105),char(110),char(116),char(77),char(97),char(120),char(70),char(111),char(114),char(99),char(101),char(0),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(77), +char(97),char(120),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(42),char(109),char(95),char(108),char(105),char(110),char(107),char(78),char(97), +char(109),char(101),char(0),char(42),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(78),char(97),char(109),char(101),char(0),char(42),char(109),char(95),char(108), +char(105),char(110),char(107),char(67),char(111),char(108),char(108),char(105),char(100),char(101),char(114),char(0),char(42),char(109),char(95),char(112),char(97),char(100),char(100),char(105), +char(110),char(103),char(80),char(116),char(114),char(0),char(109),char(95),char(98),char(97),char(115),char(101),char(87),char(111),char(114),char(108),char(100),char(84),char(114),char(97), +char(110),char(115),char(102),char(111),char(114),char(109),char(0),char(109),char(95),char(98),char(97),char(115),char(101),char(73),char(110),char(101),char(114),char(116),char(105),char(97), +char(0),char(109),char(95),char(98),char(97),char(115),char(101),char(77),char(97),char(115),char(115),char(0),char(42),char(109),char(95),char(98),char(97),char(115),char(101),char(78), +char(97),char(109),char(101),char(0),char(42),char(109),char(95),char(98),char(97),char(115),char(101),char(67),char(111),char(108),char(108),char(105),char(100),char(101),char(114),char(0), +char(84),char(89),char(80),char(69),char(95),char(0),char(0),char(0),char(99),char(104),char(97),char(114),char(0),char(117),char(99),char(104),char(97),char(114),char(0),char(115), +char(104),char(111),char(114),char(116),char(0),char(117),char(115),char(104),char(111),char(114),char(116),char(0),char(105),char(110),char(116),char(0),char(108),char(111),char(110),char(103), +char(0),char(117),char(108),char(111),char(110),char(103),char(0),char(102),char(108),char(111),char(97),char(116),char(0),char(100),char(111),char(117),char(98),char(108),char(101),char(0), +char(118),char(111),char(105),char(100),char(0),char(80),char(111),char(105),char(110),char(116),char(101),char(114),char(65),char(114),char(114),char(97),char(121),char(0),char(98),char(116), +char(80),char(104),char(121),char(115),char(105),char(99),char(115),char(83),char(121),char(115),char(116),char(101),char(109),char(0),char(76),char(105),char(115),char(116),char(66),char(97), +char(115),char(101),char(0),char(98),char(116),char(86),char(101),char(99),char(116),char(111),char(114),char(51),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116), +char(97),char(0),char(98),char(116),char(86),char(101),char(99),char(116),char(111),char(114),char(51),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116), +char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(116),char(101),char(114),char(110),char(105),char(111),char(110),char(70),char(108),char(111),char(97),char(116),char(68), +char(97),char(116),char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(116),char(101),char(114),char(110),char(105),char(111),char(110),char(68),char(111),char(117),char(98), +char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(97),char(116),char(114),char(105),char(120),char(51),char(120),char(51),char(70),char(108), +char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(97),char(116),char(114),char(105),char(120),char(51),char(120),char(51),char(68), +char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114),char(97),char(110),char(115),char(102),char(111),char(114), +char(109),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114),char(97),char(110),char(115),char(102),char(111), +char(114),char(109),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(66),char(118),char(104),char(83),char(117), +char(98),char(116),char(114),char(101),char(101),char(73),char(110),char(102),char(111),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(79),char(112),char(116),char(105), +char(109),char(105),char(122),char(101),char(100),char(66),char(118),char(104),char(78),char(111),char(100),char(101),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116), char(97),char(0),char(98),char(116),char(79),char(112),char(116),char(105),char(109),char(105),char(122),char(101),char(100),char(66),char(118),char(104),char(78),char(111),char(100),char(101), -char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(79),char(112),char(116),char(105),char(109),char(105),char(122),char(101), -char(100),char(66),char(118),char(104),char(78),char(111),char(100),char(101),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98), -char(116),char(81),char(117),char(97),char(110),char(116),char(105),char(122),char(101),char(100),char(66),char(118),char(104),char(78),char(111),char(100),char(101),char(68),char(97),char(116), -char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(110),char(116),char(105),char(122),char(101),char(100),char(66),char(118),char(104),char(70),char(108),char(111),char(97), -char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(110),char(116),char(105),char(122),char(101),char(100),char(66),char(118),char(104), -char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(108),char(108),char(105),char(115),char(105), -char(111),char(110),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(116),char(97),char(116),char(105),char(99), -char(80),char(108),char(97),char(110),char(101),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110), -char(118),char(101),char(120),char(73),char(110),char(116),char(101),char(114),char(110),char(97),char(108),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97), -char(0),char(98),char(116),char(80),char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(65),char(110),char(100),char(82),char(97),char(100),char(105),char(117),char(115), -char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),char(83),char(112),char(104),char(101),char(114),char(101),char(83),char(104),char(97),char(112),char(101),char(68), -char(97),char(116),char(97),char(0),char(98),char(116),char(73),char(110),char(116),char(73),char(110),char(100),char(101),char(120),char(68),char(97),char(116),char(97),char(0),char(98), -char(116),char(83),char(104),char(111),char(114),char(116),char(73),char(110),char(116),char(73),char(110),char(100),char(101),char(120),char(68),char(97),char(116),char(97),char(0),char(98), -char(116),char(83),char(104),char(111),char(114),char(116),char(73),char(110),char(116),char(73),char(110),char(100),char(101),char(120),char(84),char(114),char(105),char(112),char(108),char(101), -char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(104),char(97),char(114),char(73),char(110),char(100),char(101),char(120),char(84),char(114),char(105), -char(112),char(108),char(101),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(101),char(115),char(104),char(80),char(97),char(114),char(116),char(68), -char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(116),char(114),char(105),char(100),char(105),char(110),char(103),char(77),char(101),char(115),char(104),char(73),char(110), -char(116),char(101),char(114),char(102),char(97),char(99),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114),char(105),char(97),char(110),char(103), -char(108),char(101),char(77),char(101),char(115),char(104),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114), -char(105),char(97),char(110),char(103),char(108),char(101),char(73),char(110),char(102),char(111),char(77),char(97),char(112),char(68),char(97),char(116),char(97),char(0),char(98),char(116), -char(83),char(99),char(97),char(108),char(101),char(100),char(84),char(114),char(105),char(97),char(110),char(103),char(108),char(101),char(77),char(101),char(115),char(104),char(83),char(104), -char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(109),char(112),char(111),char(117),char(110),char(100),char(83),char(104), -char(97),char(112),char(101),char(67),char(104),char(105),char(108),char(100),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(109),char(112),char(111), -char(117),char(110),char(100),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(121),char(108),char(105),char(110), -char(100),char(101),char(114),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(101),char(83), -char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(97),char(112),char(115),char(117),char(108),char(101),char(83),char(104), +char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(110),char(116),char(105),char(122), +char(101),char(100),char(66),char(118),char(104),char(78),char(111),char(100),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(110), +char(116),char(105),char(122),char(101),char(100),char(66),char(118),char(104),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116), +char(81),char(117),char(97),char(110),char(116),char(105),char(122),char(101),char(100),char(66),char(118),char(104),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97), +char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(83),char(104),char(97),char(112),char(101),char(68), +char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(116),char(97),char(116),char(105),char(99),char(80),char(108),char(97),char(110),char(101),char(83),char(104),char(97), +char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(118),char(101),char(120),char(73),char(110),char(116),char(101),char(114), +char(110),char(97),char(108),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(80),char(111),char(115),char(105),char(116), +char(105),char(111),char(110),char(65),char(110),char(100),char(82),char(97),char(100),char(105),char(117),char(115),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105), +char(83),char(112),char(104),char(101),char(114),char(101),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(73),char(110), +char(116),char(73),char(110),char(100),char(101),char(120),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(104),char(111),char(114),char(116),char(73),char(110), +char(116),char(73),char(110),char(100),char(101),char(120),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(104),char(111),char(114),char(116),char(73),char(110), +char(116),char(73),char(110),char(100),char(101),char(120),char(84),char(114),char(105),char(112),char(108),char(101),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116), +char(67),char(104),char(97),char(114),char(73),char(110),char(100),char(101),char(120),char(84),char(114),char(105),char(112),char(108),char(101),char(116),char(68),char(97),char(116),char(97), +char(0),char(98),char(116),char(77),char(101),char(115),char(104),char(80),char(97),char(114),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(116), +char(114),char(105),char(100),char(105),char(110),char(103),char(77),char(101),char(115),char(104),char(73),char(110),char(116),char(101),char(114),char(102),char(97),char(99),char(101),char(68), +char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114),char(105),char(97),char(110),char(103),char(108),char(101),char(77),char(101),char(115),char(104),char(83),char(104), char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114),char(105),char(97),char(110),char(103),char(108),char(101),char(73),char(110), -char(102),char(111),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(80),char(101),char(114),char(115),char(105),char(115),char(116),char(101),char(110),char(116),char(77), -char(97),char(110),char(105),char(102),char(111),char(108),char(100),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116), -char(67),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(79),char(98),char(106),char(101),char(99),char(116),char(68),char(111),char(117),char(98),char(108), -char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(80),char(101),char(114),char(115),char(105),char(115),char(116),char(101),char(110),char(116),char(77),char(97), -char(110),char(105),char(102),char(111),char(108),char(100),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111), -char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(79),char(98),char(106),char(101),char(99),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97), -char(116),char(97),char(0),char(98),char(116),char(71),char(73),char(109),char(112),char(97),char(99),char(116),char(77),char(101),char(115),char(104),char(83),char(104),char(97),char(112), -char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(118),char(101),char(120),char(72),char(117),char(108),char(108),char(83),char(104), -char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(83),char(111),char(108), -char(118),char(101),char(114),char(73),char(110),char(102),char(111),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116), -char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(83),char(111),char(108),char(118),char(101),char(114),char(73),char(110),char(102),char(111),char(70),char(108),char(111), -char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(68),char(121),char(110),char(97),char(109),char(105),char(99),char(115),char(87),char(111),char(114), -char(108),char(100),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(68),char(121),char(110),char(97),char(109), -char(105),char(99),char(115),char(87),char(111),char(114),char(108),char(100),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116), -char(82),char(105),char(103),char(105),char(100),char(66),char(111),char(100),char(121),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98), -char(116),char(82),char(105),char(103),char(105),char(100),char(66),char(111),char(100),char(121),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97), -char(0),char(98),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(73),char(110),char(102),char(111),char(49),char(0),char(98), -char(116),char(84),char(121),char(112),char(101),char(100),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(108),char(111),char(97), -char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(121),char(112),char(101),char(100),char(67),char(111),char(110),char(115),char(116),char(114),char(97), -char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(82),char(105),char(103),char(105),char(100),char(66),char(111),char(100),char(121),char(68), -char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(121),char(112),char(101),char(100),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110), -char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(80),char(111),char(105),char(110),char(116),char(50), -char(80),char(111),char(105),char(110),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(108),char(111),char(97),char(116), -char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(80),char(111),char(105),char(110),char(116),char(50),char(80),char(111),char(105),char(110),char(116),char(67),char(111), -char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(50),char(0), -char(98),char(116),char(80),char(111),char(105),char(110),char(116),char(50),char(80),char(111),char(105),char(110),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97), -char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(72),char(105),char(110),char(103), -char(101),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116), -char(97),char(0),char(98),char(116),char(72),char(105),char(110),char(103),char(101),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(70), -char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(72),char(105),char(110),char(103),char(101),char(67),char(111),char(110),char(115), -char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(50),char(0),char(98),char(116), -char(67),char(111),char(110),char(101),char(84),char(119),char(105),char(115),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68), -char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(101),char(84),char(119),char(105),char(115), -char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101), -char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68), -char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(67),char(111),char(110), -char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(50),char(0),char(98), -char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(83),char(112),char(114),char(105),char(110),char(103),char(67),char(111), -char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114), -char(105),char(99),char(54),char(68),char(111),char(102),char(83),char(112),char(114),char(105),char(110),char(103),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105), -char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(50),char(0),char(98),char(116),char(71),char(101),char(110),char(101), -char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(83),char(112),char(114),char(105),char(110),char(103),char(50),char(67),char(111),char(110),char(115),char(116),char(114), -char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68), -char(111),char(102),char(83),char(112),char(114),char(105),char(110),char(103),char(50),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68), -char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(50),char(0),char(98),char(116),char(83),char(108),char(105),char(100),char(101),char(114),char(67), -char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(108),char(105),char(100), -char(101),char(114),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97), -char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(97),char(114),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(70), -char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(97),char(114),char(67),char(111),char(110),char(115),char(116), -char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116), -char(66),char(111),char(100),char(121),char(77),char(97),char(116),char(101),char(114),char(105),char(97),char(108),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102), -char(116),char(66),char(111),char(100),char(121),char(78),char(111),char(100),char(101),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111), -char(100),char(121),char(76),char(105),char(110),char(107),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(70), -char(97),char(99),char(101),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(84),char(101),char(116),char(114), -char(97),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(82),char(105),char(103),char(105),char(100),char(65),char(110),char(99),char(104),char(111), -char(114),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(67),char(111),char(110),char(102),char(105),char(103), -char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(80),char(111),char(115),char(101),char(68),char(97),char(116), -char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(67),char(108),char(117),char(115),char(116),char(101),char(114),char(68),char(97),char(116), -char(97),char(0),char(98),char(116),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(74),char(111),char(105),char(110),char(116),char(68),char(97),char(116), -char(97),char(0),char(98),char(116),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116), -char(97),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(76),char(105),char(110),char(107),char(68),char(111),char(117), -char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(76), -char(105),char(110),char(107),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105), -char(66),char(111),char(100),char(121),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117),char(108), -char(116),char(105),char(66),char(111),char(100),char(121),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117), -char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(76),char(105),char(110),char(107),char(67),char(111),char(108),char(108),char(105),char(100),char(101),char(114),char(70), -char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121), -char(76),char(105),char(110),char(107),char(67),char(111),char(108),char(108),char(105),char(100),char(101),char(114),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97), -char(116),char(97),char(0),char(0),char(84),char(76),char(69),char(78),char(1),char(0),char(1),char(0),char(2),char(0),char(2),char(0),char(4),char(0),char(4),char(0), -char(4),char(0),char(4),char(0),char(8),char(0),char(0),char(0),char(12),char(0),char(36),char(0),char(8),char(0),char(16),char(0),char(32),char(0),char(16),char(0), -char(32),char(0),char(48),char(0),char(96),char(0),char(64),char(0),char(-128),char(0),char(20),char(0),char(48),char(0),char(80),char(0),char(16),char(0),char(84),char(0), -char(-124),char(0),char(12),char(0),char(52),char(0),char(52),char(0),char(20),char(0),char(64),char(0),char(4),char(0),char(4),char(0),char(8),char(0),char(4),char(0), -char(32),char(0),char(28),char(0),char(60),char(0),char(56),char(0),char(76),char(0),char(76),char(0),char(24),char(0),char(60),char(0),char(60),char(0),char(60),char(0), -char(16),char(0),char(-16),char(5),char(-24),char(1),char(56),char(3),char(16),char(1),char(64),char(0),char(68),char(0),char(-104),char(0),char(88),char(0),char(-72),char(0), -char(104),char(0),char(-8),char(1),char(-72),char(3),char(8),char(0),char(52),char(0),char(52),char(0),char(0),char(0),char(68),char(0),char(84),char(0),char(-124),char(0), +char(102),char(111),char(77),char(97),char(112),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(99),char(97),char(108),char(101),char(100),char(84),char(114), +char(105),char(97),char(110),char(103),char(108),char(101),char(77),char(101),char(115),char(104),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0), +char(98),char(116),char(67),char(111),char(109),char(112),char(111),char(117),char(110),char(100),char(83),char(104),char(97),char(112),char(101),char(67),char(104),char(105),char(108),char(100), +char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(109),char(112),char(111),char(117),char(110),char(100),char(83),char(104),char(97),char(112),char(101), +char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(121),char(108),char(105),char(110),char(100),char(101),char(114),char(83),char(104),char(97),char(112),char(101), +char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(101),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97), +char(0),char(98),char(116),char(67),char(97),char(112),char(115),char(117),char(108),char(101),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0), +char(98),char(116),char(84),char(114),char(105),char(97),char(110),char(103),char(108),char(101),char(73),char(110),char(102),char(111),char(68),char(97),char(116),char(97),char(0),char(98), +char(116),char(71),char(73),char(109),char(112),char(97),char(99),char(116),char(77),char(101),char(115),char(104),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116), +char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(118),char(101),char(120),char(72),char(117),char(108),char(108),char(83),char(104),char(97),char(112),char(101),char(68), +char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(79),char(98),char(106),char(101),char(99), +char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(108),char(108),char(105),char(115), +char(105),char(111),char(110),char(79),char(98),char(106),char(101),char(99),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98), +char(116),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(83),char(111),char(108),char(118),char(101),char(114),char(73),char(110),char(102),char(111),char(68),char(111), +char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(83),char(111), +char(108),char(118),char(101),char(114),char(73),char(110),char(102),char(111),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116), +char(68),char(121),char(110),char(97),char(109),char(105),char(99),char(115),char(87),char(111),char(114),char(108),char(100),char(68),char(111),char(117),char(98),char(108),char(101),char(68), +char(97),char(116),char(97),char(0),char(98),char(116),char(68),char(121),char(110),char(97),char(109),char(105),char(99),char(115),char(87),char(111),char(114),char(108),char(100),char(70), +char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(82),char(105),char(103),char(105),char(100),char(66),char(111),char(100),char(121), +char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(82),char(105),char(103),char(105),char(100),char(66),char(111),char(100), +char(121),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(115),char(116),char(114), +char(97),char(105),char(110),char(116),char(73),char(110),char(102),char(111),char(49),char(0),char(98),char(116),char(84),char(121),char(112),char(101),char(100),char(67),char(111),char(110), +char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84), +char(121),char(112),char(101),char(100),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98), +char(116),char(82),char(105),char(103),char(105),char(100),char(66),char(111),char(100),char(121),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(121),char(112), +char(101),char(100),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97), +char(116),char(97),char(0),char(98),char(116),char(80),char(111),char(105),char(110),char(116),char(50),char(80),char(111),char(105),char(110),char(116),char(67),char(111),char(110),char(115), +char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(80),char(111), +char(105),char(110),char(116),char(50),char(80),char(111),char(105),char(110),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68), +char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(50),char(0),char(98),char(116),char(80),char(111),char(105),char(110),char(116),char(50),char(80), +char(111),char(105),char(110),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101), +char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(72),char(105),char(110),char(103),char(101),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105), +char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(72),char(105),char(110),char(103),char(101), +char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0), +char(98),char(116),char(72),char(105),char(110),char(103),char(101),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117), +char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(50),char(0),char(98),char(116),char(67),char(111),char(110),char(101),char(84),char(119),char(105),char(115),char(116), +char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97), +char(0),char(98),char(116),char(67),char(111),char(110),char(101),char(84),char(119),char(105),char(115),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105), +char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102), +char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(110), +char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111), +char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(50),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54), +char(68),char(111),char(102),char(83),char(112),char(114),char(105),char(110),char(103),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68), +char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(83),char(112),char(114), +char(105),char(110),char(103),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68), +char(97),char(116),char(97),char(50),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(83),char(112), +char(114),char(105),char(110),char(103),char(50),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0), +char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(83),char(112),char(114),char(105),char(110),char(103),char(50), +char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97), +char(50),char(0),char(98),char(116),char(83),char(108),char(105),char(100),char(101),char(114),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116), +char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(108),char(105),char(100),char(101),char(114),char(67),char(111),char(110),char(115),char(116),char(114),char(97), +char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(97),char(114), +char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0), +char(98),char(116),char(71),char(101),char(97),char(114),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98), +char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(77),char(97),char(116),char(101),char(114), +char(105),char(97),char(108),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(78),char(111),char(100),char(101), +char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(76),char(105),char(110),char(107),char(68),char(97),char(116), +char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(70),char(97),char(99),char(101),char(68),char(97),char(116),char(97),char(0),char(83), +char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(84),char(101),char(116),char(114),char(97),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102), +char(116),char(82),char(105),char(103),char(105),char(100),char(65),char(110),char(99),char(104),char(111),char(114),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102), +char(116),char(66),char(111),char(100),char(121),char(67),char(111),char(110),char(102),char(105),char(103),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116), +char(66),char(111),char(100),char(121),char(80),char(111),char(115),char(101),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100), +char(121),char(67),char(108),char(117),char(115),char(116),char(101),char(114),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(111),char(102),char(116),char(66), +char(111),char(100),char(121),char(74),char(111),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(111),char(102),char(116),char(66), +char(111),char(100),char(121),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105), +char(66),char(111),char(100),char(121),char(76),char(105),char(110),char(107),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98), +char(116),char(77),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(76),char(105),char(110),char(107),char(70),char(108),char(111),char(97),char(116),char(68), +char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(68),char(111),char(117),char(98),char(108), +char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(70),char(108),char(111), +char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(0),char(84),char(76),char(69),char(78),char(1),char(0),char(1),char(0),char(2),char(0),char(2),char(0), +char(4),char(0),char(4),char(0),char(4),char(0),char(4),char(0),char(8),char(0),char(0),char(0),char(12),char(0),char(36),char(0),char(8),char(0),char(16),char(0), +char(32),char(0),char(16),char(0),char(32),char(0),char(48),char(0),char(96),char(0),char(64),char(0),char(-128),char(0),char(20),char(0),char(48),char(0),char(80),char(0), +char(16),char(0),char(84),char(0),char(-124),char(0),char(12),char(0),char(52),char(0),char(52),char(0),char(20),char(0),char(64),char(0),char(4),char(0),char(4),char(0), +char(8),char(0),char(4),char(0),char(32),char(0),char(28),char(0),char(60),char(0),char(56),char(0),char(76),char(0),char(76),char(0),char(24),char(0),char(60),char(0), +char(60),char(0),char(60),char(0),char(16),char(0),char(64),char(0),char(68),char(0),char(-32),char(1),char(8),char(1),char(-104),char(0),char(88),char(0),char(-72),char(0), +char(104),char(0),char(-16),char(1),char(-80),char(3),char(8),char(0),char(52),char(0),char(52),char(0),char(0),char(0),char(68),char(0),char(84),char(0),char(-124),char(0), char(116),char(0),char(92),char(1),char(-36),char(0),char(-116),char(1),char(124),char(1),char(-44),char(0),char(-4),char(0),char(-52),char(1),char(92),char(1),char(116),char(2), char(-124),char(2),char(-76),char(4),char(-52),char(0),char(108),char(1),char(92),char(0),char(-116),char(0),char(16),char(0),char(100),char(0),char(20),char(0),char(36),char(0), -char(100),char(0),char(92),char(0),char(104),char(0),char(-64),char(0),char(92),char(1),char(104),char(0),char(-68),char(1),char(112),char(3),char(-56),char(1),char(-68),char(0), -char(100),char(0),char(28),char(1),char(-12),char(1),char(0),char(0),char(83),char(84),char(82),char(67),char(88),char(0),char(0),char(0),char(10),char(0),char(3),char(0), -char(4),char(0),char(0),char(0),char(4),char(0),char(1),char(0),char(9),char(0),char(2),char(0),char(11),char(0),char(3),char(0),char(10),char(0),char(3),char(0), -char(10),char(0),char(4),char(0),char(10),char(0),char(5),char(0),char(12),char(0),char(2),char(0),char(9),char(0),char(6),char(0),char(9),char(0),char(7),char(0), -char(13),char(0),char(1),char(0),char(7),char(0),char(8),char(0),char(14),char(0),char(1),char(0),char(8),char(0),char(8),char(0),char(15),char(0),char(1),char(0), -char(7),char(0),char(8),char(0),char(16),char(0),char(1),char(0),char(8),char(0),char(8),char(0),char(17),char(0),char(1),char(0),char(13),char(0),char(9),char(0), -char(18),char(0),char(1),char(0),char(14),char(0),char(9),char(0),char(19),char(0),char(2),char(0),char(17),char(0),char(10),char(0),char(13),char(0),char(11),char(0), -char(20),char(0),char(2),char(0),char(18),char(0),char(10),char(0),char(14),char(0),char(11),char(0),char(21),char(0),char(4),char(0),char(4),char(0),char(12),char(0), -char(4),char(0),char(13),char(0),char(2),char(0),char(14),char(0),char(2),char(0),char(15),char(0),char(22),char(0),char(6),char(0),char(13),char(0),char(16),char(0), -char(13),char(0),char(17),char(0),char(4),char(0),char(18),char(0),char(4),char(0),char(19),char(0),char(4),char(0),char(20),char(0),char(0),char(0),char(21),char(0), -char(23),char(0),char(6),char(0),char(14),char(0),char(16),char(0),char(14),char(0),char(17),char(0),char(4),char(0),char(18),char(0),char(4),char(0),char(19),char(0), -char(4),char(0),char(20),char(0),char(0),char(0),char(21),char(0),char(24),char(0),char(3),char(0),char(2),char(0),char(14),char(0),char(2),char(0),char(15),char(0), -char(4),char(0),char(22),char(0),char(25),char(0),char(12),char(0),char(13),char(0),char(23),char(0),char(13),char(0),char(24),char(0),char(13),char(0),char(25),char(0), -char(4),char(0),char(26),char(0),char(4),char(0),char(27),char(0),char(4),char(0),char(28),char(0),char(4),char(0),char(29),char(0),char(22),char(0),char(30),char(0), -char(24),char(0),char(31),char(0),char(21),char(0),char(32),char(0),char(4),char(0),char(33),char(0),char(4),char(0),char(34),char(0),char(26),char(0),char(12),char(0), -char(14),char(0),char(23),char(0),char(14),char(0),char(24),char(0),char(14),char(0),char(25),char(0),char(4),char(0),char(26),char(0),char(4),char(0),char(27),char(0), -char(4),char(0),char(28),char(0),char(4),char(0),char(29),char(0),char(23),char(0),char(30),char(0),char(24),char(0),char(31),char(0),char(4),char(0),char(33),char(0), -char(4),char(0),char(34),char(0),char(21),char(0),char(32),char(0),char(27),char(0),char(3),char(0),char(0),char(0),char(35),char(0),char(4),char(0),char(36),char(0), -char(0),char(0),char(37),char(0),char(28),char(0),char(5),char(0),char(27),char(0),char(38),char(0),char(13),char(0),char(39),char(0),char(13),char(0),char(40),char(0), -char(7),char(0),char(41),char(0),char(0),char(0),char(21),char(0),char(29),char(0),char(5),char(0),char(27),char(0),char(38),char(0),char(13),char(0),char(39),char(0), -char(13),char(0),char(42),char(0),char(7),char(0),char(43),char(0),char(4),char(0),char(44),char(0),char(30),char(0),char(2),char(0),char(13),char(0),char(45),char(0), -char(7),char(0),char(46),char(0),char(31),char(0),char(4),char(0),char(29),char(0),char(47),char(0),char(30),char(0),char(48),char(0),char(4),char(0),char(49),char(0), -char(0),char(0),char(37),char(0),char(32),char(0),char(1),char(0),char(4),char(0),char(50),char(0),char(33),char(0),char(2),char(0),char(2),char(0),char(50),char(0), -char(0),char(0),char(51),char(0),char(34),char(0),char(2),char(0),char(2),char(0),char(52),char(0),char(0),char(0),char(51),char(0),char(35),char(0),char(2),char(0), -char(0),char(0),char(52),char(0),char(0),char(0),char(53),char(0),char(36),char(0),char(8),char(0),char(13),char(0),char(54),char(0),char(14),char(0),char(55),char(0), -char(32),char(0),char(56),char(0),char(34),char(0),char(57),char(0),char(35),char(0),char(58),char(0),char(33),char(0),char(59),char(0),char(4),char(0),char(60),char(0), -char(4),char(0),char(61),char(0),char(37),char(0),char(4),char(0),char(36),char(0),char(62),char(0),char(13),char(0),char(63),char(0),char(4),char(0),char(64),char(0), -char(0),char(0),char(37),char(0),char(38),char(0),char(7),char(0),char(27),char(0),char(38),char(0),char(37),char(0),char(65),char(0),char(25),char(0),char(66),char(0), -char(26),char(0),char(67),char(0),char(39),char(0),char(68),char(0),char(7),char(0),char(43),char(0),char(0),char(0),char(69),char(0),char(40),char(0),char(2),char(0), -char(38),char(0),char(70),char(0),char(13),char(0),char(39),char(0),char(41),char(0),char(4),char(0),char(19),char(0),char(71),char(0),char(27),char(0),char(72),char(0), -char(4),char(0),char(73),char(0),char(7),char(0),char(74),char(0),char(42),char(0),char(4),char(0),char(27),char(0),char(38),char(0),char(41),char(0),char(75),char(0), -char(4),char(0),char(76),char(0),char(7),char(0),char(43),char(0),char(43),char(0),char(3),char(0),char(29),char(0),char(47),char(0),char(4),char(0),char(77),char(0), -char(0),char(0),char(37),char(0),char(44),char(0),char(3),char(0),char(29),char(0),char(47),char(0),char(4),char(0),char(78),char(0),char(0),char(0),char(37),char(0), -char(45),char(0),char(3),char(0),char(29),char(0),char(47),char(0),char(4),char(0),char(77),char(0),char(0),char(0),char(37),char(0),char(46),char(0),char(4),char(0), -char(4),char(0),char(79),char(0),char(7),char(0),char(80),char(0),char(7),char(0),char(81),char(0),char(7),char(0),char(82),char(0),char(39),char(0),char(14),char(0), -char(4),char(0),char(83),char(0),char(4),char(0),char(84),char(0),char(46),char(0),char(85),char(0),char(4),char(0),char(86),char(0),char(7),char(0),char(87),char(0), -char(7),char(0),char(88),char(0),char(7),char(0),char(89),char(0),char(7),char(0),char(90),char(0),char(7),char(0),char(91),char(0),char(4),char(0),char(92),char(0), -char(4),char(0),char(93),char(0),char(4),char(0),char(94),char(0),char(4),char(0),char(95),char(0),char(0),char(0),char(37),char(0),char(47),char(0),char(38),char(0), -char(14),char(0),char(96),char(0),char(14),char(0),char(97),char(0),char(14),char(0),char(98),char(0),char(14),char(0),char(99),char(0),char(14),char(0),char(100),char(0), -char(14),char(0),char(101),char(0),char(14),char(0),char(102),char(0),char(8),char(0),char(103),char(0),char(8),char(0),char(104),char(0),char(8),char(0),char(105),char(0), -char(8),char(0),char(106),char(0),char(8),char(0),char(107),char(0),char(8),char(0),char(108),char(0),char(4),char(0),char(109),char(0),char(4),char(0),char(110),char(0), -char(4),char(0),char(111),char(0),char(4),char(0),char(112),char(0),char(4),char(0),char(113),char(0),char(8),char(0),char(114),char(0),char(8),char(0),char(115),char(0), -char(8),char(0),char(116),char(0),char(8),char(0),char(117),char(0),char(8),char(0),char(118),char(0),char(8),char(0),char(119),char(0),char(8),char(0),char(120),char(0), -char(8),char(0),char(121),char(0),char(8),char(0),char(122),char(0),char(4),char(0),char(123),char(0),char(4),char(0),char(124),char(0),char(4),char(0),char(125),char(0), -char(4),char(0),char(126),char(0),char(4),char(0),char(127),char(0),char(4),char(0),char(-128),char(0),char(8),char(0),char(-127),char(0),char(8),char(0),char(-126),char(0), -char(4),char(0),char(44),char(0),char(48),char(0),char(-125),char(0),char(48),char(0),char(-124),char(0),char(49),char(0),char(38),char(0),char(13),char(0),char(96),char(0), -char(13),char(0),char(97),char(0),char(13),char(0),char(98),char(0),char(13),char(0),char(99),char(0),char(13),char(0),char(100),char(0),char(13),char(0),char(101),char(0), -char(13),char(0),char(102),char(0),char(7),char(0),char(103),char(0),char(7),char(0),char(104),char(0),char(7),char(0),char(105),char(0),char(7),char(0),char(106),char(0), -char(7),char(0),char(107),char(0),char(7),char(0),char(108),char(0),char(4),char(0),char(109),char(0),char(4),char(0),char(110),char(0),char(4),char(0),char(111),char(0), -char(4),char(0),char(112),char(0),char(4),char(0),char(113),char(0),char(7),char(0),char(114),char(0),char(7),char(0),char(115),char(0),char(7),char(0),char(116),char(0), -char(7),char(0),char(117),char(0),char(7),char(0),char(118),char(0),char(7),char(0),char(119),char(0),char(7),char(0),char(120),char(0),char(7),char(0),char(121),char(0), -char(7),char(0),char(122),char(0),char(4),char(0),char(123),char(0),char(4),char(0),char(124),char(0),char(4),char(0),char(125),char(0),char(4),char(0),char(126),char(0), -char(4),char(0),char(127),char(0),char(4),char(0),char(-128),char(0),char(7),char(0),char(-127),char(0),char(7),char(0),char(-126),char(0),char(4),char(0),char(44),char(0), -char(50),char(0),char(-125),char(0),char(50),char(0),char(-124),char(0),char(51),char(0),char(5),char(0),char(27),char(0),char(38),char(0),char(37),char(0),char(65),char(0), -char(13),char(0),char(39),char(0),char(7),char(0),char(43),char(0),char(4),char(0),char(-123),char(0),char(52),char(0),char(5),char(0),char(29),char(0),char(47),char(0), -char(13),char(0),char(-122),char(0),char(14),char(0),char(-121),char(0),char(4),char(0),char(-120),char(0),char(0),char(0),char(-119),char(0),char(48),char(0),char(29),char(0), -char(9),char(0),char(-118),char(0),char(9),char(0),char(-117),char(0),char(27),char(0),char(-116),char(0),char(0),char(0),char(35),char(0),char(20),char(0),char(-115),char(0), -char(20),char(0),char(-114),char(0),char(14),char(0),char(-113),char(0),char(14),char(0),char(-112),char(0),char(14),char(0),char(-111),char(0),char(8),char(0),char(-126),char(0), -char(8),char(0),char(-110),char(0),char(8),char(0),char(-109),char(0),char(8),char(0),char(-108),char(0),char(8),char(0),char(-107),char(0),char(8),char(0),char(-106),char(0), -char(8),char(0),char(-105),char(0),char(8),char(0),char(-104),char(0),char(8),char(0),char(-103),char(0),char(8),char(0),char(-102),char(0),char(4),char(0),char(-101),char(0), -char(4),char(0),char(-100),char(0),char(4),char(0),char(-99),char(0),char(4),char(0),char(-98),char(0),char(4),char(0),char(-97),char(0),char(4),char(0),char(-96),char(0), -char(4),char(0),char(-95),char(0),char(4),char(0),char(-94),char(0),char(4),char(0),char(-93),char(0),char(4),char(0),char(-92),char(0),char(50),char(0),char(29),char(0), -char(9),char(0),char(-118),char(0),char(9),char(0),char(-117),char(0),char(27),char(0),char(-116),char(0),char(0),char(0),char(35),char(0),char(19),char(0),char(-115),char(0), -char(19),char(0),char(-114),char(0),char(13),char(0),char(-113),char(0),char(13),char(0),char(-112),char(0),char(13),char(0),char(-111),char(0),char(7),char(0),char(-126),char(0), -char(7),char(0),char(-110),char(0),char(7),char(0),char(-109),char(0),char(7),char(0),char(-108),char(0),char(7),char(0),char(-107),char(0),char(7),char(0),char(-106),char(0), -char(7),char(0),char(-105),char(0),char(7),char(0),char(-104),char(0),char(7),char(0),char(-103),char(0),char(7),char(0),char(-102),char(0),char(4),char(0),char(-101),char(0), -char(4),char(0),char(-100),char(0),char(4),char(0),char(-99),char(0),char(4),char(0),char(-98),char(0),char(4),char(0),char(-97),char(0),char(4),char(0),char(-96),char(0), -char(4),char(0),char(-95),char(0),char(4),char(0),char(-94),char(0),char(4),char(0),char(-93),char(0),char(4),char(0),char(-92),char(0),char(53),char(0),char(22),char(0), -char(8),char(0),char(-91),char(0),char(8),char(0),char(-90),char(0),char(8),char(0),char(-109),char(0),char(8),char(0),char(-89),char(0),char(8),char(0),char(-105),char(0), -char(8),char(0),char(-88),char(0),char(8),char(0),char(-87),char(0),char(8),char(0),char(-86),char(0),char(8),char(0),char(-85),char(0),char(8),char(0),char(-84),char(0), -char(8),char(0),char(-83),char(0),char(8),char(0),char(-82),char(0),char(8),char(0),char(-81),char(0),char(8),char(0),char(-80),char(0),char(8),char(0),char(-79),char(0), -char(8),char(0),char(-78),char(0),char(4),char(0),char(-77),char(0),char(4),char(0),char(-76),char(0),char(4),char(0),char(-75),char(0),char(4),char(0),char(-74),char(0), -char(4),char(0),char(-73),char(0),char(0),char(0),char(37),char(0),char(54),char(0),char(22),char(0),char(7),char(0),char(-91),char(0),char(7),char(0),char(-90),char(0), -char(7),char(0),char(-109),char(0),char(7),char(0),char(-89),char(0),char(7),char(0),char(-105),char(0),char(7),char(0),char(-88),char(0),char(7),char(0),char(-87),char(0), -char(7),char(0),char(-86),char(0),char(7),char(0),char(-85),char(0),char(7),char(0),char(-84),char(0),char(7),char(0),char(-83),char(0),char(7),char(0),char(-82),char(0), -char(7),char(0),char(-81),char(0),char(7),char(0),char(-80),char(0),char(7),char(0),char(-79),char(0),char(7),char(0),char(-78),char(0),char(4),char(0),char(-77),char(0), -char(4),char(0),char(-76),char(0),char(4),char(0),char(-75),char(0),char(4),char(0),char(-74),char(0),char(4),char(0),char(-73),char(0),char(0),char(0),char(37),char(0), -char(55),char(0),char(2),char(0),char(53),char(0),char(-72),char(0),char(14),char(0),char(-71),char(0),char(56),char(0),char(2),char(0),char(54),char(0),char(-72),char(0), -char(13),char(0),char(-71),char(0),char(57),char(0),char(21),char(0),char(50),char(0),char(-70),char(0),char(17),char(0),char(-69),char(0),char(13),char(0),char(-68),char(0), -char(13),char(0),char(-67),char(0),char(13),char(0),char(-66),char(0),char(13),char(0),char(-65),char(0),char(13),char(0),char(-71),char(0),char(13),char(0),char(-64),char(0), -char(13),char(0),char(-63),char(0),char(13),char(0),char(-62),char(0),char(13),char(0),char(-61),char(0),char(7),char(0),char(-60),char(0),char(7),char(0),char(-59),char(0), -char(7),char(0),char(-58),char(0),char(7),char(0),char(-57),char(0),char(7),char(0),char(-56),char(0),char(7),char(0),char(-55),char(0),char(7),char(0),char(-54),char(0), -char(7),char(0),char(-53),char(0),char(7),char(0),char(-52),char(0),char(4),char(0),char(-51),char(0),char(58),char(0),char(22),char(0),char(48),char(0),char(-70),char(0), -char(18),char(0),char(-69),char(0),char(14),char(0),char(-68),char(0),char(14),char(0),char(-67),char(0),char(14),char(0),char(-66),char(0),char(14),char(0),char(-65),char(0), -char(14),char(0),char(-71),char(0),char(14),char(0),char(-64),char(0),char(14),char(0),char(-63),char(0),char(14),char(0),char(-62),char(0),char(14),char(0),char(-61),char(0), -char(8),char(0),char(-60),char(0),char(8),char(0),char(-59),char(0),char(8),char(0),char(-58),char(0),char(8),char(0),char(-57),char(0),char(8),char(0),char(-56),char(0), -char(8),char(0),char(-55),char(0),char(8),char(0),char(-54),char(0),char(8),char(0),char(-53),char(0),char(8),char(0),char(-52),char(0),char(4),char(0),char(-51),char(0), -char(0),char(0),char(37),char(0),char(59),char(0),char(2),char(0),char(4),char(0),char(-50),char(0),char(4),char(0),char(-49),char(0),char(60),char(0),char(13),char(0), -char(57),char(0),char(-48),char(0),char(57),char(0),char(-47),char(0),char(0),char(0),char(35),char(0),char(4),char(0),char(-128),char(0),char(4),char(0),char(-46),char(0), -char(4),char(0),char(-45),char(0),char(4),char(0),char(-44),char(0),char(7),char(0),char(-43),char(0),char(7),char(0),char(-42),char(0),char(4),char(0),char(-41),char(0), -char(4),char(0),char(-40),char(0),char(7),char(0),char(-39),char(0),char(4),char(0),char(-38),char(0),char(61),char(0),char(13),char(0),char(62),char(0),char(-48),char(0), -char(62),char(0),char(-47),char(0),char(0),char(0),char(35),char(0),char(4),char(0),char(-128),char(0),char(4),char(0),char(-46),char(0),char(4),char(0),char(-45),char(0), -char(4),char(0),char(-44),char(0),char(7),char(0),char(-43),char(0),char(7),char(0),char(-42),char(0),char(4),char(0),char(-41),char(0),char(4),char(0),char(-40),char(0), -char(7),char(0),char(-39),char(0),char(4),char(0),char(-38),char(0),char(63),char(0),char(14),char(0),char(58),char(0),char(-48),char(0),char(58),char(0),char(-47),char(0), -char(0),char(0),char(35),char(0),char(4),char(0),char(-128),char(0),char(4),char(0),char(-46),char(0),char(4),char(0),char(-45),char(0),char(4),char(0),char(-44),char(0), -char(8),char(0),char(-43),char(0),char(8),char(0),char(-42),char(0),char(4),char(0),char(-41),char(0),char(4),char(0),char(-40),char(0),char(8),char(0),char(-39),char(0), -char(4),char(0),char(-38),char(0),char(0),char(0),char(-37),char(0),char(64),char(0),char(3),char(0),char(61),char(0),char(-36),char(0),char(13),char(0),char(-35),char(0), -char(13),char(0),char(-34),char(0),char(65),char(0),char(3),char(0),char(63),char(0),char(-36),char(0),char(14),char(0),char(-35),char(0),char(14),char(0),char(-34),char(0), -char(66),char(0),char(3),char(0),char(61),char(0),char(-36),char(0),char(14),char(0),char(-35),char(0),char(14),char(0),char(-34),char(0),char(67),char(0),char(13),char(0), -char(61),char(0),char(-36),char(0),char(20),char(0),char(-33),char(0),char(20),char(0),char(-32),char(0),char(4),char(0),char(-31),char(0),char(4),char(0),char(-30),char(0), -char(4),char(0),char(-29),char(0),char(7),char(0),char(-28),char(0),char(7),char(0),char(-27),char(0),char(7),char(0),char(-26),char(0),char(7),char(0),char(-25),char(0), -char(7),char(0),char(-24),char(0),char(7),char(0),char(-23),char(0),char(7),char(0),char(-22),char(0),char(68),char(0),char(13),char(0),char(61),char(0),char(-36),char(0), -char(19),char(0),char(-33),char(0),char(19),char(0),char(-32),char(0),char(4),char(0),char(-31),char(0),char(4),char(0),char(-30),char(0),char(4),char(0),char(-29),char(0), -char(7),char(0),char(-28),char(0),char(7),char(0),char(-27),char(0),char(7),char(0),char(-26),char(0),char(7),char(0),char(-25),char(0),char(7),char(0),char(-24),char(0), -char(7),char(0),char(-23),char(0),char(7),char(0),char(-22),char(0),char(69),char(0),char(14),char(0),char(63),char(0),char(-36),char(0),char(20),char(0),char(-33),char(0), -char(20),char(0),char(-32),char(0),char(4),char(0),char(-31),char(0),char(4),char(0),char(-30),char(0),char(4),char(0),char(-29),char(0),char(8),char(0),char(-28),char(0), -char(8),char(0),char(-27),char(0),char(8),char(0),char(-26),char(0),char(8),char(0),char(-25),char(0),char(8),char(0),char(-24),char(0),char(8),char(0),char(-23),char(0), -char(8),char(0),char(-22),char(0),char(0),char(0),char(-21),char(0),char(70),char(0),char(10),char(0),char(63),char(0),char(-36),char(0),char(20),char(0),char(-33),char(0), -char(20),char(0),char(-32),char(0),char(8),char(0),char(-20),char(0),char(8),char(0),char(-19),char(0),char(8),char(0),char(-18),char(0),char(8),char(0),char(-24),char(0), -char(8),char(0),char(-23),char(0),char(8),char(0),char(-22),char(0),char(8),char(0),char(-90),char(0),char(71),char(0),char(11),char(0),char(61),char(0),char(-36),char(0), -char(19),char(0),char(-33),char(0),char(19),char(0),char(-32),char(0),char(7),char(0),char(-20),char(0),char(7),char(0),char(-19),char(0),char(7),char(0),char(-18),char(0), -char(7),char(0),char(-24),char(0),char(7),char(0),char(-23),char(0),char(7),char(0),char(-22),char(0),char(7),char(0),char(-90),char(0),char(0),char(0),char(21),char(0), -char(72),char(0),char(9),char(0),char(61),char(0),char(-36),char(0),char(19),char(0),char(-33),char(0),char(19),char(0),char(-32),char(0),char(13),char(0),char(-17),char(0), -char(13),char(0),char(-16),char(0),char(13),char(0),char(-15),char(0),char(13),char(0),char(-14),char(0),char(4),char(0),char(-13),char(0),char(4),char(0),char(-12),char(0), -char(73),char(0),char(9),char(0),char(63),char(0),char(-36),char(0),char(20),char(0),char(-33),char(0),char(20),char(0),char(-32),char(0),char(14),char(0),char(-17),char(0), -char(14),char(0),char(-16),char(0),char(14),char(0),char(-15),char(0),char(14),char(0),char(-14),char(0),char(4),char(0),char(-13),char(0),char(4),char(0),char(-12),char(0), -char(74),char(0),char(5),char(0),char(72),char(0),char(-11),char(0),char(4),char(0),char(-10),char(0),char(7),char(0),char(-9),char(0),char(7),char(0),char(-8),char(0), -char(7),char(0),char(-7),char(0),char(75),char(0),char(5),char(0),char(73),char(0),char(-11),char(0),char(4),char(0),char(-10),char(0),char(8),char(0),char(-9),char(0), -char(8),char(0),char(-8),char(0),char(8),char(0),char(-7),char(0),char(76),char(0),char(41),char(0),char(61),char(0),char(-36),char(0),char(19),char(0),char(-33),char(0), -char(19),char(0),char(-32),char(0),char(13),char(0),char(-17),char(0),char(13),char(0),char(-16),char(0),char(13),char(0),char(-6),char(0),char(13),char(0),char(-5),char(0), -char(13),char(0),char(-4),char(0),char(13),char(0),char(-3),char(0),char(13),char(0),char(-2),char(0),char(13),char(0),char(-1),char(0),char(13),char(0),char(0),char(1), -char(13),char(0),char(1),char(1),char(13),char(0),char(2),char(1),char(13),char(0),char(3),char(1),char(13),char(0),char(4),char(1),char(0),char(0),char(5),char(1), -char(0),char(0),char(6),char(1),char(0),char(0),char(7),char(1),char(0),char(0),char(8),char(1),char(0),char(0),char(9),char(1),char(0),char(0),char(-21),char(0), -char(13),char(0),char(-15),char(0),char(13),char(0),char(-14),char(0),char(13),char(0),char(10),char(1),char(13),char(0),char(11),char(1),char(13),char(0),char(12),char(1), -char(13),char(0),char(13),char(1),char(13),char(0),char(14),char(1),char(13),char(0),char(15),char(1),char(13),char(0),char(16),char(1),char(13),char(0),char(17),char(1), -char(13),char(0),char(18),char(1),char(13),char(0),char(19),char(1),char(13),char(0),char(20),char(1),char(0),char(0),char(21),char(1),char(0),char(0),char(22),char(1), -char(0),char(0),char(23),char(1),char(0),char(0),char(24),char(1),char(0),char(0),char(25),char(1),char(4),char(0),char(26),char(1),char(77),char(0),char(41),char(0), -char(63),char(0),char(-36),char(0),char(20),char(0),char(-33),char(0),char(20),char(0),char(-32),char(0),char(14),char(0),char(-17),char(0),char(14),char(0),char(-16),char(0), -char(14),char(0),char(-6),char(0),char(14),char(0),char(-5),char(0),char(14),char(0),char(-4),char(0),char(14),char(0),char(-3),char(0),char(14),char(0),char(-2),char(0), -char(14),char(0),char(-1),char(0),char(14),char(0),char(0),char(1),char(14),char(0),char(1),char(1),char(14),char(0),char(2),char(1),char(14),char(0),char(3),char(1), -char(14),char(0),char(4),char(1),char(0),char(0),char(5),char(1),char(0),char(0),char(6),char(1),char(0),char(0),char(7),char(1),char(0),char(0),char(8),char(1), -char(0),char(0),char(9),char(1),char(0),char(0),char(-21),char(0),char(14),char(0),char(-15),char(0),char(14),char(0),char(-14),char(0),char(14),char(0),char(10),char(1), -char(14),char(0),char(11),char(1),char(14),char(0),char(12),char(1),char(14),char(0),char(13),char(1),char(14),char(0),char(14),char(1),char(14),char(0),char(15),char(1), -char(14),char(0),char(16),char(1),char(14),char(0),char(17),char(1),char(14),char(0),char(18),char(1),char(14),char(0),char(19),char(1),char(14),char(0),char(20),char(1), -char(0),char(0),char(21),char(1),char(0),char(0),char(22),char(1),char(0),char(0),char(23),char(1),char(0),char(0),char(24),char(1),char(0),char(0),char(25),char(1), -char(4),char(0),char(26),char(1),char(78),char(0),char(9),char(0),char(61),char(0),char(-36),char(0),char(19),char(0),char(-33),char(0),char(19),char(0),char(-32),char(0), -char(7),char(0),char(-17),char(0),char(7),char(0),char(-16),char(0),char(7),char(0),char(-15),char(0),char(7),char(0),char(-14),char(0),char(4),char(0),char(-13),char(0), -char(4),char(0),char(-12),char(0),char(79),char(0),char(9),char(0),char(63),char(0),char(-36),char(0),char(20),char(0),char(-33),char(0),char(20),char(0),char(-32),char(0), -char(8),char(0),char(-17),char(0),char(8),char(0),char(-16),char(0),char(8),char(0),char(-15),char(0),char(8),char(0),char(-14),char(0),char(4),char(0),char(-13),char(0), -char(4),char(0),char(-12),char(0),char(80),char(0),char(5),char(0),char(60),char(0),char(-36),char(0),char(13),char(0),char(27),char(1),char(13),char(0),char(28),char(1), -char(7),char(0),char(29),char(1),char(0),char(0),char(37),char(0),char(81),char(0),char(4),char(0),char(63),char(0),char(-36),char(0),char(14),char(0),char(27),char(1), -char(14),char(0),char(28),char(1),char(8),char(0),char(29),char(1),char(82),char(0),char(4),char(0),char(7),char(0),char(30),char(1),char(7),char(0),char(31),char(1), -char(7),char(0),char(32),char(1),char(4),char(0),char(79),char(0),char(83),char(0),char(10),char(0),char(82),char(0),char(33),char(1),char(13),char(0),char(34),char(1), -char(13),char(0),char(35),char(1),char(13),char(0),char(36),char(1),char(13),char(0),char(37),char(1),char(13),char(0),char(38),char(1),char(7),char(0),char(-60),char(0), -char(7),char(0),char(39),char(1),char(4),char(0),char(40),char(1),char(4),char(0),char(53),char(0),char(84),char(0),char(4),char(0),char(82),char(0),char(33),char(1), -char(4),char(0),char(41),char(1),char(7),char(0),char(42),char(1),char(4),char(0),char(43),char(1),char(85),char(0),char(4),char(0),char(13),char(0),char(38),char(1), -char(82),char(0),char(33),char(1),char(4),char(0),char(44),char(1),char(7),char(0),char(45),char(1),char(86),char(0),char(7),char(0),char(13),char(0),char(46),char(1), -char(82),char(0),char(33),char(1),char(4),char(0),char(47),char(1),char(7),char(0),char(48),char(1),char(7),char(0),char(49),char(1),char(7),char(0),char(50),char(1), -char(4),char(0),char(53),char(0),char(87),char(0),char(6),char(0),char(17),char(0),char(51),char(1),char(13),char(0),char(49),char(1),char(13),char(0),char(52),char(1), -char(62),char(0),char(53),char(1),char(4),char(0),char(54),char(1),char(7),char(0),char(50),char(1),char(88),char(0),char(26),char(0),char(4),char(0),char(55),char(1), -char(7),char(0),char(56),char(1),char(7),char(0),char(-90),char(0),char(7),char(0),char(57),char(1),char(7),char(0),char(58),char(1),char(7),char(0),char(59),char(1), -char(7),char(0),char(60),char(1),char(7),char(0),char(61),char(1),char(7),char(0),char(62),char(1),char(7),char(0),char(63),char(1),char(7),char(0),char(64),char(1), -char(7),char(0),char(65),char(1),char(7),char(0),char(66),char(1),char(7),char(0),char(67),char(1),char(7),char(0),char(68),char(1),char(7),char(0),char(69),char(1), -char(7),char(0),char(70),char(1),char(7),char(0),char(71),char(1),char(7),char(0),char(72),char(1),char(7),char(0),char(73),char(1),char(7),char(0),char(74),char(1), -char(4),char(0),char(75),char(1),char(4),char(0),char(76),char(1),char(4),char(0),char(77),char(1),char(4),char(0),char(78),char(1),char(4),char(0),char(-100),char(0), -char(89),char(0),char(12),char(0),char(17),char(0),char(79),char(1),char(17),char(0),char(80),char(1),char(17),char(0),char(81),char(1),char(13),char(0),char(82),char(1), -char(13),char(0),char(83),char(1),char(7),char(0),char(84),char(1),char(4),char(0),char(85),char(1),char(4),char(0),char(86),char(1),char(4),char(0),char(87),char(1), -char(4),char(0),char(88),char(1),char(7),char(0),char(48),char(1),char(4),char(0),char(53),char(0),char(90),char(0),char(27),char(0),char(19),char(0),char(89),char(1), -char(17),char(0),char(90),char(1),char(17),char(0),char(91),char(1),char(13),char(0),char(82),char(1),char(13),char(0),char(92),char(1),char(13),char(0),char(93),char(1), -char(13),char(0),char(94),char(1),char(13),char(0),char(95),char(1),char(13),char(0),char(96),char(1),char(4),char(0),char(97),char(1),char(7),char(0),char(98),char(1), -char(4),char(0),char(99),char(1),char(4),char(0),char(100),char(1),char(4),char(0),char(101),char(1),char(7),char(0),char(102),char(1),char(7),char(0),char(103),char(1), -char(4),char(0),char(104),char(1),char(4),char(0),char(105),char(1),char(7),char(0),char(106),char(1),char(7),char(0),char(107),char(1),char(7),char(0),char(108),char(1), -char(7),char(0),char(109),char(1),char(7),char(0),char(110),char(1),char(7),char(0),char(111),char(1),char(4),char(0),char(112),char(1),char(4),char(0),char(113),char(1), -char(4),char(0),char(114),char(1),char(91),char(0),char(12),char(0),char(9),char(0),char(115),char(1),char(9),char(0),char(116),char(1),char(13),char(0),char(117),char(1), -char(7),char(0),char(118),char(1),char(7),char(0),char(-86),char(0),char(7),char(0),char(119),char(1),char(4),char(0),char(120),char(1),char(13),char(0),char(121),char(1), -char(4),char(0),char(122),char(1),char(4),char(0),char(123),char(1),char(4),char(0),char(124),char(1),char(4),char(0),char(53),char(0),char(92),char(0),char(19),char(0), -char(50),char(0),char(-70),char(0),char(89),char(0),char(125),char(1),char(82),char(0),char(126),char(1),char(83),char(0),char(127),char(1),char(84),char(0),char(-128),char(1), -char(85),char(0),char(-127),char(1),char(86),char(0),char(-126),char(1),char(87),char(0),char(-125),char(1),char(90),char(0),char(-124),char(1),char(91),char(0),char(-123),char(1), -char(4),char(0),char(-122),char(1),char(4),char(0),char(100),char(1),char(4),char(0),char(-121),char(1),char(4),char(0),char(-120),char(1),char(4),char(0),char(-119),char(1), -char(4),char(0),char(-118),char(1),char(4),char(0),char(-117),char(1),char(4),char(0),char(-116),char(1),char(88),char(0),char(-115),char(1),char(93),char(0),char(28),char(0), -char(16),char(0),char(-114),char(1),char(14),char(0),char(-113),char(1),char(14),char(0),char(-112),char(1),char(14),char(0),char(-111),char(1),char(14),char(0),char(-110),char(1), -char(14),char(0),char(-109),char(1),char(14),char(0),char(-108),char(1),char(14),char(0),char(-107),char(1),char(14),char(0),char(-106),char(1),char(14),char(0),char(-105),char(1), -char(8),char(0),char(-104),char(1),char(4),char(0),char(-103),char(1),char(4),char(0),char(124),char(1),char(4),char(0),char(-102),char(1),char(4),char(0),char(-101),char(1), -char(8),char(0),char(-100),char(1),char(8),char(0),char(-99),char(1),char(8),char(0),char(-98),char(1),char(8),char(0),char(-97),char(1),char(8),char(0),char(-96),char(1), -char(8),char(0),char(-95),char(1),char(8),char(0),char(-94),char(1),char(8),char(0),char(-93),char(1),char(8),char(0),char(-92),char(1),char(0),char(0),char(-91),char(1), -char(0),char(0),char(-90),char(1),char(48),char(0),char(-89),char(1),char(0),char(0),char(-88),char(1),char(94),char(0),char(28),char(0),char(15),char(0),char(-114),char(1), -char(13),char(0),char(-113),char(1),char(13),char(0),char(-112),char(1),char(13),char(0),char(-111),char(1),char(13),char(0),char(-110),char(1),char(13),char(0),char(-109),char(1), -char(13),char(0),char(-108),char(1),char(13),char(0),char(-107),char(1),char(13),char(0),char(-106),char(1),char(13),char(0),char(-105),char(1),char(4),char(0),char(-102),char(1), -char(7),char(0),char(-104),char(1),char(4),char(0),char(-103),char(1),char(4),char(0),char(124),char(1),char(7),char(0),char(-100),char(1),char(7),char(0),char(-99),char(1), -char(7),char(0),char(-98),char(1),char(4),char(0),char(-101),char(1),char(7),char(0),char(-97),char(1),char(7),char(0),char(-96),char(1),char(7),char(0),char(-95),char(1), -char(7),char(0),char(-94),char(1),char(7),char(0),char(-93),char(1),char(7),char(0),char(-92),char(1),char(0),char(0),char(-91),char(1),char(0),char(0),char(-90),char(1), -char(50),char(0),char(-89),char(1),char(0),char(0),char(-88),char(1),char(95),char(0),char(11),char(0),char(14),char(0),char(-87),char(1),char(16),char(0),char(-86),char(1), -char(14),char(0),char(-85),char(1),char(14),char(0),char(-84),char(1),char(14),char(0),char(-83),char(1),char(8),char(0),char(-82),char(1),char(4),char(0),char(-121),char(1), -char(0),char(0),char(37),char(0),char(0),char(0),char(-81),char(1),char(93),char(0),char(-128),char(1),char(48),char(0),char(-80),char(1),char(96),char(0),char(10),char(0), -char(13),char(0),char(-87),char(1),char(15),char(0),char(-86),char(1),char(13),char(0),char(-85),char(1),char(13),char(0),char(-84),char(1),char(13),char(0),char(-83),char(1), -char(7),char(0),char(-82),char(1),char(4),char(0),char(-121),char(1),char(0),char(0),char(-81),char(1),char(94),char(0),char(-128),char(1),char(50),char(0),char(-80),char(1), -char(97),char(0),char(4),char(0),char(50),char(0),char(-79),char(1),char(96),char(0),char(-78),char(1),char(4),char(0),char(-77),char(1),char(0),char(0),char(37),char(0), -char(98),char(0),char(4),char(0),char(48),char(0),char(-79),char(1),char(95),char(0),char(-78),char(1),char(4),char(0),char(-77),char(1),char(0),char(0),char(37),char(0), -}; +char(100),char(0),char(92),char(0),char(104),char(0),char(-64),char(0),char(92),char(1),char(104),char(0),char(-76),char(1),char(-16),char(2),char(-120),char(1),char(-64),char(0), +char(100),char(0),char(0),char(0),char(83),char(84),char(82),char(67),char(84),char(0),char(0),char(0),char(10),char(0),char(3),char(0),char(4),char(0),char(0),char(0), +char(4),char(0),char(1),char(0),char(9),char(0),char(2),char(0),char(11),char(0),char(3),char(0),char(10),char(0),char(3),char(0),char(10),char(0),char(4),char(0), +char(10),char(0),char(5),char(0),char(12),char(0),char(2),char(0),char(9),char(0),char(6),char(0),char(9),char(0),char(7),char(0),char(13),char(0),char(1),char(0), +char(7),char(0),char(8),char(0),char(14),char(0),char(1),char(0),char(8),char(0),char(8),char(0),char(15),char(0),char(1),char(0),char(7),char(0),char(8),char(0), +char(16),char(0),char(1),char(0),char(8),char(0),char(8),char(0),char(17),char(0),char(1),char(0),char(13),char(0),char(9),char(0),char(18),char(0),char(1),char(0), +char(14),char(0),char(9),char(0),char(19),char(0),char(2),char(0),char(17),char(0),char(10),char(0),char(13),char(0),char(11),char(0),char(20),char(0),char(2),char(0), +char(18),char(0),char(10),char(0),char(14),char(0),char(11),char(0),char(21),char(0),char(4),char(0),char(4),char(0),char(12),char(0),char(4),char(0),char(13),char(0), +char(2),char(0),char(14),char(0),char(2),char(0),char(15),char(0),char(22),char(0),char(6),char(0),char(13),char(0),char(16),char(0),char(13),char(0),char(17),char(0), +char(4),char(0),char(18),char(0),char(4),char(0),char(19),char(0),char(4),char(0),char(20),char(0),char(0),char(0),char(21),char(0),char(23),char(0),char(6),char(0), +char(14),char(0),char(16),char(0),char(14),char(0),char(17),char(0),char(4),char(0),char(18),char(0),char(4),char(0),char(19),char(0),char(4),char(0),char(20),char(0), +char(0),char(0),char(21),char(0),char(24),char(0),char(3),char(0),char(2),char(0),char(14),char(0),char(2),char(0),char(15),char(0),char(4),char(0),char(22),char(0), +char(25),char(0),char(12),char(0),char(13),char(0),char(23),char(0),char(13),char(0),char(24),char(0),char(13),char(0),char(25),char(0),char(4),char(0),char(26),char(0), +char(4),char(0),char(27),char(0),char(4),char(0),char(28),char(0),char(4),char(0),char(29),char(0),char(22),char(0),char(30),char(0),char(24),char(0),char(31),char(0), +char(21),char(0),char(32),char(0),char(4),char(0),char(33),char(0),char(4),char(0),char(34),char(0),char(26),char(0),char(12),char(0),char(14),char(0),char(23),char(0), +char(14),char(0),char(24),char(0),char(14),char(0),char(25),char(0),char(4),char(0),char(26),char(0),char(4),char(0),char(27),char(0),char(4),char(0),char(28),char(0), +char(4),char(0),char(29),char(0),char(23),char(0),char(30),char(0),char(24),char(0),char(31),char(0),char(4),char(0),char(33),char(0),char(4),char(0),char(34),char(0), +char(21),char(0),char(32),char(0),char(27),char(0),char(3),char(0),char(0),char(0),char(35),char(0),char(4),char(0),char(36),char(0),char(0),char(0),char(37),char(0), +char(28),char(0),char(5),char(0),char(27),char(0),char(38),char(0),char(13),char(0),char(39),char(0),char(13),char(0),char(40),char(0),char(7),char(0),char(41),char(0), +char(0),char(0),char(21),char(0),char(29),char(0),char(5),char(0),char(27),char(0),char(38),char(0),char(13),char(0),char(39),char(0),char(13),char(0),char(42),char(0), +char(7),char(0),char(43),char(0),char(4),char(0),char(44),char(0),char(30),char(0),char(2),char(0),char(13),char(0),char(45),char(0),char(7),char(0),char(46),char(0), +char(31),char(0),char(4),char(0),char(29),char(0),char(47),char(0),char(30),char(0),char(48),char(0),char(4),char(0),char(49),char(0),char(0),char(0),char(37),char(0), +char(32),char(0),char(1),char(0),char(4),char(0),char(50),char(0),char(33),char(0),char(2),char(0),char(2),char(0),char(50),char(0),char(0),char(0),char(51),char(0), +char(34),char(0),char(2),char(0),char(2),char(0),char(52),char(0),char(0),char(0),char(51),char(0),char(35),char(0),char(2),char(0),char(0),char(0),char(52),char(0), +char(0),char(0),char(53),char(0),char(36),char(0),char(8),char(0),char(13),char(0),char(54),char(0),char(14),char(0),char(55),char(0),char(32),char(0),char(56),char(0), +char(34),char(0),char(57),char(0),char(35),char(0),char(58),char(0),char(33),char(0),char(59),char(0),char(4),char(0),char(60),char(0),char(4),char(0),char(61),char(0), +char(37),char(0),char(4),char(0),char(36),char(0),char(62),char(0),char(13),char(0),char(63),char(0),char(4),char(0),char(64),char(0),char(0),char(0),char(37),char(0), +char(38),char(0),char(7),char(0),char(27),char(0),char(38),char(0),char(37),char(0),char(65),char(0),char(25),char(0),char(66),char(0),char(26),char(0),char(67),char(0), +char(39),char(0),char(68),char(0),char(7),char(0),char(43),char(0),char(0),char(0),char(69),char(0),char(40),char(0),char(2),char(0),char(38),char(0),char(70),char(0), +char(13),char(0),char(39),char(0),char(41),char(0),char(4),char(0),char(19),char(0),char(71),char(0),char(27),char(0),char(72),char(0),char(4),char(0),char(73),char(0), +char(7),char(0),char(74),char(0),char(42),char(0),char(4),char(0),char(27),char(0),char(38),char(0),char(41),char(0),char(75),char(0),char(4),char(0),char(76),char(0), +char(7),char(0),char(43),char(0),char(43),char(0),char(3),char(0),char(29),char(0),char(47),char(0),char(4),char(0),char(77),char(0),char(0),char(0),char(37),char(0), +char(44),char(0),char(3),char(0),char(29),char(0),char(47),char(0),char(4),char(0),char(78),char(0),char(0),char(0),char(37),char(0),char(45),char(0),char(3),char(0), +char(29),char(0),char(47),char(0),char(4),char(0),char(77),char(0),char(0),char(0),char(37),char(0),char(46),char(0),char(4),char(0),char(4),char(0),char(79),char(0), +char(7),char(0),char(80),char(0),char(7),char(0),char(81),char(0),char(7),char(0),char(82),char(0),char(39),char(0),char(14),char(0),char(4),char(0),char(83),char(0), +char(4),char(0),char(84),char(0),char(46),char(0),char(85),char(0),char(4),char(0),char(86),char(0),char(7),char(0),char(87),char(0),char(7),char(0),char(88),char(0), +char(7),char(0),char(89),char(0),char(7),char(0),char(90),char(0),char(7),char(0),char(91),char(0),char(4),char(0),char(92),char(0),char(4),char(0),char(93),char(0), +char(4),char(0),char(94),char(0),char(4),char(0),char(95),char(0),char(0),char(0),char(37),char(0),char(47),char(0),char(5),char(0),char(27),char(0),char(38),char(0), +char(37),char(0),char(65),char(0),char(13),char(0),char(39),char(0),char(7),char(0),char(43),char(0),char(4),char(0),char(96),char(0),char(48),char(0),char(5),char(0), +char(29),char(0),char(47),char(0),char(13),char(0),char(97),char(0),char(14),char(0),char(98),char(0),char(4),char(0),char(99),char(0),char(0),char(0),char(100),char(0), +char(49),char(0),char(27),char(0),char(9),char(0),char(101),char(0),char(9),char(0),char(102),char(0),char(27),char(0),char(103),char(0),char(0),char(0),char(35),char(0), +char(20),char(0),char(104),char(0),char(20),char(0),char(105),char(0),char(14),char(0),char(106),char(0),char(14),char(0),char(107),char(0),char(14),char(0),char(108),char(0), +char(8),char(0),char(109),char(0),char(8),char(0),char(110),char(0),char(8),char(0),char(111),char(0),char(8),char(0),char(112),char(0),char(8),char(0),char(113),char(0), +char(8),char(0),char(114),char(0),char(8),char(0),char(115),char(0),char(8),char(0),char(116),char(0),char(8),char(0),char(117),char(0),char(8),char(0),char(118),char(0), +char(4),char(0),char(119),char(0),char(4),char(0),char(120),char(0),char(4),char(0),char(121),char(0),char(4),char(0),char(122),char(0),char(4),char(0),char(123),char(0), +char(4),char(0),char(124),char(0),char(4),char(0),char(125),char(0),char(0),char(0),char(37),char(0),char(50),char(0),char(27),char(0),char(9),char(0),char(101),char(0), +char(9),char(0),char(102),char(0),char(27),char(0),char(103),char(0),char(0),char(0),char(35),char(0),char(19),char(0),char(104),char(0),char(19),char(0),char(105),char(0), +char(13),char(0),char(106),char(0),char(13),char(0),char(107),char(0),char(13),char(0),char(108),char(0),char(7),char(0),char(109),char(0),char(7),char(0),char(110),char(0), +char(7),char(0),char(111),char(0),char(7),char(0),char(112),char(0),char(7),char(0),char(113),char(0),char(7),char(0),char(114),char(0),char(7),char(0),char(115),char(0), +char(7),char(0),char(116),char(0),char(7),char(0),char(117),char(0),char(7),char(0),char(118),char(0),char(4),char(0),char(119),char(0),char(4),char(0),char(120),char(0), +char(4),char(0),char(121),char(0),char(4),char(0),char(122),char(0),char(4),char(0),char(123),char(0),char(4),char(0),char(124),char(0),char(4),char(0),char(125),char(0), +char(0),char(0),char(37),char(0),char(51),char(0),char(22),char(0),char(8),char(0),char(126),char(0),char(8),char(0),char(127),char(0),char(8),char(0),char(111),char(0), +char(8),char(0),char(-128),char(0),char(8),char(0),char(115),char(0),char(8),char(0),char(-127),char(0),char(8),char(0),char(-126),char(0),char(8),char(0),char(-125),char(0), +char(8),char(0),char(-124),char(0),char(8),char(0),char(-123),char(0),char(8),char(0),char(-122),char(0),char(8),char(0),char(-121),char(0),char(8),char(0),char(-120),char(0), +char(8),char(0),char(-119),char(0),char(8),char(0),char(-118),char(0),char(8),char(0),char(-117),char(0),char(4),char(0),char(-116),char(0),char(4),char(0),char(-115),char(0), +char(4),char(0),char(-114),char(0),char(4),char(0),char(-113),char(0),char(4),char(0),char(-112),char(0),char(0),char(0),char(37),char(0),char(52),char(0),char(22),char(0), +char(7),char(0),char(126),char(0),char(7),char(0),char(127),char(0),char(7),char(0),char(111),char(0),char(7),char(0),char(-128),char(0),char(7),char(0),char(115),char(0), +char(7),char(0),char(-127),char(0),char(7),char(0),char(-126),char(0),char(7),char(0),char(-125),char(0),char(7),char(0),char(-124),char(0),char(7),char(0),char(-123),char(0), +char(7),char(0),char(-122),char(0),char(7),char(0),char(-121),char(0),char(7),char(0),char(-120),char(0),char(7),char(0),char(-119),char(0),char(7),char(0),char(-118),char(0), +char(7),char(0),char(-117),char(0),char(4),char(0),char(-116),char(0),char(4),char(0),char(-115),char(0),char(4),char(0),char(-114),char(0),char(4),char(0),char(-113),char(0), +char(4),char(0),char(-112),char(0),char(0),char(0),char(37),char(0),char(53),char(0),char(2),char(0),char(51),char(0),char(-111),char(0),char(14),char(0),char(-110),char(0), +char(54),char(0),char(2),char(0),char(52),char(0),char(-111),char(0),char(13),char(0),char(-110),char(0),char(55),char(0),char(21),char(0),char(50),char(0),char(-109),char(0), +char(17),char(0),char(-108),char(0),char(13),char(0),char(-107),char(0),char(13),char(0),char(-106),char(0),char(13),char(0),char(-105),char(0),char(13),char(0),char(-104),char(0), +char(13),char(0),char(-110),char(0),char(13),char(0),char(-103),char(0),char(13),char(0),char(-102),char(0),char(13),char(0),char(-101),char(0),char(13),char(0),char(-100),char(0), +char(7),char(0),char(-99),char(0),char(7),char(0),char(-98),char(0),char(7),char(0),char(-97),char(0),char(7),char(0),char(-96),char(0),char(7),char(0),char(-95),char(0), +char(7),char(0),char(-94),char(0),char(7),char(0),char(-93),char(0),char(7),char(0),char(-92),char(0),char(7),char(0),char(-91),char(0),char(4),char(0),char(-90),char(0), +char(56),char(0),char(22),char(0),char(49),char(0),char(-109),char(0),char(18),char(0),char(-108),char(0),char(14),char(0),char(-107),char(0),char(14),char(0),char(-106),char(0), +char(14),char(0),char(-105),char(0),char(14),char(0),char(-104),char(0),char(14),char(0),char(-110),char(0),char(14),char(0),char(-103),char(0),char(14),char(0),char(-102),char(0), +char(14),char(0),char(-101),char(0),char(14),char(0),char(-100),char(0),char(8),char(0),char(-99),char(0),char(8),char(0),char(-98),char(0),char(8),char(0),char(-97),char(0), +char(8),char(0),char(-96),char(0),char(8),char(0),char(-95),char(0),char(8),char(0),char(-94),char(0),char(8),char(0),char(-93),char(0),char(8),char(0),char(-92),char(0), +char(8),char(0),char(-91),char(0),char(4),char(0),char(-90),char(0),char(0),char(0),char(37),char(0),char(57),char(0),char(2),char(0),char(4),char(0),char(-89),char(0), +char(4),char(0),char(-88),char(0),char(58),char(0),char(13),char(0),char(55),char(0),char(-87),char(0),char(55),char(0),char(-86),char(0),char(0),char(0),char(35),char(0), +char(4),char(0),char(-85),char(0),char(4),char(0),char(-84),char(0),char(4),char(0),char(-83),char(0),char(4),char(0),char(-82),char(0),char(7),char(0),char(-81),char(0), +char(7),char(0),char(-80),char(0),char(4),char(0),char(-79),char(0),char(4),char(0),char(-78),char(0),char(7),char(0),char(-77),char(0),char(4),char(0),char(-76),char(0), +char(59),char(0),char(13),char(0),char(60),char(0),char(-87),char(0),char(60),char(0),char(-86),char(0),char(0),char(0),char(35),char(0),char(4),char(0),char(-85),char(0), +char(4),char(0),char(-84),char(0),char(4),char(0),char(-83),char(0),char(4),char(0),char(-82),char(0),char(7),char(0),char(-81),char(0),char(7),char(0),char(-80),char(0), +char(4),char(0),char(-79),char(0),char(4),char(0),char(-78),char(0),char(7),char(0),char(-77),char(0),char(4),char(0),char(-76),char(0),char(61),char(0),char(14),char(0), +char(56),char(0),char(-87),char(0),char(56),char(0),char(-86),char(0),char(0),char(0),char(35),char(0),char(4),char(0),char(-85),char(0),char(4),char(0),char(-84),char(0), +char(4),char(0),char(-83),char(0),char(4),char(0),char(-82),char(0),char(8),char(0),char(-81),char(0),char(8),char(0),char(-80),char(0),char(4),char(0),char(-79),char(0), +char(4),char(0),char(-78),char(0),char(8),char(0),char(-77),char(0),char(4),char(0),char(-76),char(0),char(0),char(0),char(-75),char(0),char(62),char(0),char(3),char(0), +char(59),char(0),char(-74),char(0),char(13),char(0),char(-73),char(0),char(13),char(0),char(-72),char(0),char(63),char(0),char(3),char(0),char(61),char(0),char(-74),char(0), +char(14),char(0),char(-73),char(0),char(14),char(0),char(-72),char(0),char(64),char(0),char(3),char(0),char(59),char(0),char(-74),char(0),char(14),char(0),char(-73),char(0), +char(14),char(0),char(-72),char(0),char(65),char(0),char(13),char(0),char(59),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0), +char(4),char(0),char(-69),char(0),char(4),char(0),char(-68),char(0),char(4),char(0),char(-67),char(0),char(7),char(0),char(-66),char(0),char(7),char(0),char(-65),char(0), +char(7),char(0),char(-64),char(0),char(7),char(0),char(-63),char(0),char(7),char(0),char(-62),char(0),char(7),char(0),char(-61),char(0),char(7),char(0),char(-60),char(0), +char(66),char(0),char(13),char(0),char(59),char(0),char(-74),char(0),char(19),char(0),char(-71),char(0),char(19),char(0),char(-70),char(0),char(4),char(0),char(-69),char(0), +char(4),char(0),char(-68),char(0),char(4),char(0),char(-67),char(0),char(7),char(0),char(-66),char(0),char(7),char(0),char(-65),char(0),char(7),char(0),char(-64),char(0), +char(7),char(0),char(-63),char(0),char(7),char(0),char(-62),char(0),char(7),char(0),char(-61),char(0),char(7),char(0),char(-60),char(0),char(67),char(0),char(14),char(0), +char(61),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),char(4),char(0),char(-69),char(0),char(4),char(0),char(-68),char(0), +char(4),char(0),char(-67),char(0),char(8),char(0),char(-66),char(0),char(8),char(0),char(-65),char(0),char(8),char(0),char(-64),char(0),char(8),char(0),char(-63),char(0), +char(8),char(0),char(-62),char(0),char(8),char(0),char(-61),char(0),char(8),char(0),char(-60),char(0),char(0),char(0),char(-59),char(0),char(68),char(0),char(10),char(0), +char(61),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),char(8),char(0),char(-58),char(0),char(8),char(0),char(-57),char(0), +char(8),char(0),char(-56),char(0),char(8),char(0),char(-62),char(0),char(8),char(0),char(-61),char(0),char(8),char(0),char(-60),char(0),char(8),char(0),char(127),char(0), +char(69),char(0),char(11),char(0),char(59),char(0),char(-74),char(0),char(19),char(0),char(-71),char(0),char(19),char(0),char(-70),char(0),char(7),char(0),char(-58),char(0), +char(7),char(0),char(-57),char(0),char(7),char(0),char(-56),char(0),char(7),char(0),char(-62),char(0),char(7),char(0),char(-61),char(0),char(7),char(0),char(-60),char(0), +char(7),char(0),char(127),char(0),char(0),char(0),char(21),char(0),char(70),char(0),char(9),char(0),char(59),char(0),char(-74),char(0),char(19),char(0),char(-71),char(0), +char(19),char(0),char(-70),char(0),char(13),char(0),char(-55),char(0),char(13),char(0),char(-54),char(0),char(13),char(0),char(-53),char(0),char(13),char(0),char(-52),char(0), +char(4),char(0),char(-51),char(0),char(4),char(0),char(-50),char(0),char(71),char(0),char(9),char(0),char(61),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0), +char(20),char(0),char(-70),char(0),char(14),char(0),char(-55),char(0),char(14),char(0),char(-54),char(0),char(14),char(0),char(-53),char(0),char(14),char(0),char(-52),char(0), +char(4),char(0),char(-51),char(0),char(4),char(0),char(-50),char(0),char(72),char(0),char(5),char(0),char(70),char(0),char(-49),char(0),char(4),char(0),char(-48),char(0), +char(7),char(0),char(-47),char(0),char(7),char(0),char(-46),char(0),char(7),char(0),char(-45),char(0),char(73),char(0),char(5),char(0),char(71),char(0),char(-49),char(0), +char(4),char(0),char(-48),char(0),char(8),char(0),char(-47),char(0),char(8),char(0),char(-46),char(0),char(8),char(0),char(-45),char(0),char(74),char(0),char(41),char(0), +char(59),char(0),char(-74),char(0),char(19),char(0),char(-71),char(0),char(19),char(0),char(-70),char(0),char(13),char(0),char(-55),char(0),char(13),char(0),char(-54),char(0), +char(13),char(0),char(-44),char(0),char(13),char(0),char(-43),char(0),char(13),char(0),char(-42),char(0),char(13),char(0),char(-41),char(0),char(13),char(0),char(-40),char(0), +char(13),char(0),char(-39),char(0),char(13),char(0),char(-38),char(0),char(13),char(0),char(-37),char(0),char(13),char(0),char(-36),char(0),char(13),char(0),char(-35),char(0), +char(13),char(0),char(-34),char(0),char(0),char(0),char(-33),char(0),char(0),char(0),char(-32),char(0),char(0),char(0),char(-31),char(0),char(0),char(0),char(-30),char(0), +char(0),char(0),char(-29),char(0),char(0),char(0),char(-59),char(0),char(13),char(0),char(-53),char(0),char(13),char(0),char(-52),char(0),char(13),char(0),char(-28),char(0), +char(13),char(0),char(-27),char(0),char(13),char(0),char(-26),char(0),char(13),char(0),char(-25),char(0),char(13),char(0),char(-24),char(0),char(13),char(0),char(-23),char(0), +char(13),char(0),char(-22),char(0),char(13),char(0),char(-21),char(0),char(13),char(0),char(-20),char(0),char(13),char(0),char(-19),char(0),char(13),char(0),char(-18),char(0), +char(0),char(0),char(-17),char(0),char(0),char(0),char(-16),char(0),char(0),char(0),char(-15),char(0),char(0),char(0),char(-14),char(0),char(0),char(0),char(-13),char(0), +char(4),char(0),char(-12),char(0),char(75),char(0),char(41),char(0),char(61),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0), +char(14),char(0),char(-55),char(0),char(14),char(0),char(-54),char(0),char(14),char(0),char(-44),char(0),char(14),char(0),char(-43),char(0),char(14),char(0),char(-42),char(0), +char(14),char(0),char(-41),char(0),char(14),char(0),char(-40),char(0),char(14),char(0),char(-39),char(0),char(14),char(0),char(-38),char(0),char(14),char(0),char(-37),char(0), +char(14),char(0),char(-36),char(0),char(14),char(0),char(-35),char(0),char(14),char(0),char(-34),char(0),char(0),char(0),char(-33),char(0),char(0),char(0),char(-32),char(0), +char(0),char(0),char(-31),char(0),char(0),char(0),char(-30),char(0),char(0),char(0),char(-29),char(0),char(0),char(0),char(-59),char(0),char(14),char(0),char(-53),char(0), +char(14),char(0),char(-52),char(0),char(14),char(0),char(-28),char(0),char(14),char(0),char(-27),char(0),char(14),char(0),char(-26),char(0),char(14),char(0),char(-25),char(0), +char(14),char(0),char(-24),char(0),char(14),char(0),char(-23),char(0),char(14),char(0),char(-22),char(0),char(14),char(0),char(-21),char(0),char(14),char(0),char(-20),char(0), +char(14),char(0),char(-19),char(0),char(14),char(0),char(-18),char(0),char(0),char(0),char(-17),char(0),char(0),char(0),char(-16),char(0),char(0),char(0),char(-15),char(0), +char(0),char(0),char(-14),char(0),char(0),char(0),char(-13),char(0),char(4),char(0),char(-12),char(0),char(76),char(0),char(9),char(0),char(59),char(0),char(-74),char(0), +char(19),char(0),char(-71),char(0),char(19),char(0),char(-70),char(0),char(7),char(0),char(-55),char(0),char(7),char(0),char(-54),char(0),char(7),char(0),char(-53),char(0), +char(7),char(0),char(-52),char(0),char(4),char(0),char(-51),char(0),char(4),char(0),char(-50),char(0),char(77),char(0),char(9),char(0),char(61),char(0),char(-74),char(0), +char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),char(8),char(0),char(-55),char(0),char(8),char(0),char(-54),char(0),char(8),char(0),char(-53),char(0), +char(8),char(0),char(-52),char(0),char(4),char(0),char(-51),char(0),char(4),char(0),char(-50),char(0),char(78),char(0),char(5),char(0),char(58),char(0),char(-74),char(0), +char(13),char(0),char(-11),char(0),char(13),char(0),char(-10),char(0),char(7),char(0),char(-9),char(0),char(0),char(0),char(37),char(0),char(79),char(0),char(4),char(0), +char(61),char(0),char(-74),char(0),char(14),char(0),char(-11),char(0),char(14),char(0),char(-10),char(0),char(8),char(0),char(-9),char(0),char(80),char(0),char(4),char(0), +char(7),char(0),char(-8),char(0),char(7),char(0),char(-7),char(0),char(7),char(0),char(-6),char(0),char(4),char(0),char(79),char(0),char(81),char(0),char(10),char(0), +char(80),char(0),char(-5),char(0),char(13),char(0),char(-4),char(0),char(13),char(0),char(-3),char(0),char(13),char(0),char(-2),char(0),char(13),char(0),char(-1),char(0), +char(13),char(0),char(0),char(1),char(7),char(0),char(-99),char(0),char(7),char(0),char(1),char(1),char(4),char(0),char(2),char(1),char(4),char(0),char(53),char(0), +char(82),char(0),char(4),char(0),char(80),char(0),char(-5),char(0),char(4),char(0),char(3),char(1),char(7),char(0),char(4),char(1),char(4),char(0),char(5),char(1), +char(83),char(0),char(4),char(0),char(13),char(0),char(0),char(1),char(80),char(0),char(-5),char(0),char(4),char(0),char(6),char(1),char(7),char(0),char(7),char(1), +char(84),char(0),char(7),char(0),char(13),char(0),char(8),char(1),char(80),char(0),char(-5),char(0),char(4),char(0),char(9),char(1),char(7),char(0),char(10),char(1), +char(7),char(0),char(11),char(1),char(7),char(0),char(12),char(1),char(4),char(0),char(53),char(0),char(85),char(0),char(6),char(0),char(17),char(0),char(13),char(1), +char(13),char(0),char(11),char(1),char(13),char(0),char(14),char(1),char(60),char(0),char(15),char(1),char(4),char(0),char(16),char(1),char(7),char(0),char(12),char(1), +char(86),char(0),char(26),char(0),char(4),char(0),char(17),char(1),char(7),char(0),char(18),char(1),char(7),char(0),char(127),char(0),char(7),char(0),char(19),char(1), +char(7),char(0),char(20),char(1),char(7),char(0),char(21),char(1),char(7),char(0),char(22),char(1),char(7),char(0),char(23),char(1),char(7),char(0),char(24),char(1), +char(7),char(0),char(25),char(1),char(7),char(0),char(26),char(1),char(7),char(0),char(27),char(1),char(7),char(0),char(28),char(1),char(7),char(0),char(29),char(1), +char(7),char(0),char(30),char(1),char(7),char(0),char(31),char(1),char(7),char(0),char(32),char(1),char(7),char(0),char(33),char(1),char(7),char(0),char(34),char(1), +char(7),char(0),char(35),char(1),char(7),char(0),char(36),char(1),char(4),char(0),char(37),char(1),char(4),char(0),char(38),char(1),char(4),char(0),char(39),char(1), +char(4),char(0),char(40),char(1),char(4),char(0),char(120),char(0),char(87),char(0),char(12),char(0),char(17),char(0),char(41),char(1),char(17),char(0),char(42),char(1), +char(17),char(0),char(43),char(1),char(13),char(0),char(44),char(1),char(13),char(0),char(45),char(1),char(7),char(0),char(46),char(1),char(4),char(0),char(47),char(1), +char(4),char(0),char(48),char(1),char(4),char(0),char(49),char(1),char(4),char(0),char(50),char(1),char(7),char(0),char(10),char(1),char(4),char(0),char(53),char(0), +char(88),char(0),char(27),char(0),char(19),char(0),char(51),char(1),char(17),char(0),char(52),char(1),char(17),char(0),char(53),char(1),char(13),char(0),char(44),char(1), +char(13),char(0),char(54),char(1),char(13),char(0),char(55),char(1),char(13),char(0),char(56),char(1),char(13),char(0),char(57),char(1),char(13),char(0),char(58),char(1), +char(4),char(0),char(59),char(1),char(7),char(0),char(60),char(1),char(4),char(0),char(61),char(1),char(4),char(0),char(62),char(1),char(4),char(0),char(63),char(1), +char(7),char(0),char(64),char(1),char(7),char(0),char(65),char(1),char(4),char(0),char(66),char(1),char(4),char(0),char(67),char(1),char(7),char(0),char(68),char(1), +char(7),char(0),char(69),char(1),char(7),char(0),char(70),char(1),char(7),char(0),char(71),char(1),char(7),char(0),char(72),char(1),char(7),char(0),char(73),char(1), +char(4),char(0),char(74),char(1),char(4),char(0),char(75),char(1),char(4),char(0),char(76),char(1),char(89),char(0),char(12),char(0),char(9),char(0),char(77),char(1), +char(9),char(0),char(78),char(1),char(13),char(0),char(79),char(1),char(7),char(0),char(80),char(1),char(7),char(0),char(-125),char(0),char(7),char(0),char(81),char(1), +char(4),char(0),char(82),char(1),char(13),char(0),char(83),char(1),char(4),char(0),char(84),char(1),char(4),char(0),char(85),char(1),char(4),char(0),char(86),char(1), +char(4),char(0),char(53),char(0),char(90),char(0),char(19),char(0),char(50),char(0),char(-109),char(0),char(87),char(0),char(87),char(1),char(80),char(0),char(88),char(1), +char(81),char(0),char(89),char(1),char(82),char(0),char(90),char(1),char(83),char(0),char(91),char(1),char(84),char(0),char(92),char(1),char(85),char(0),char(93),char(1), +char(88),char(0),char(94),char(1),char(89),char(0),char(95),char(1),char(4),char(0),char(96),char(1),char(4),char(0),char(62),char(1),char(4),char(0),char(97),char(1), +char(4),char(0),char(98),char(1),char(4),char(0),char(99),char(1),char(4),char(0),char(100),char(1),char(4),char(0),char(101),char(1),char(4),char(0),char(102),char(1), +char(86),char(0),char(103),char(1),char(91),char(0),char(24),char(0),char(16),char(0),char(104),char(1),char(14),char(0),char(105),char(1),char(14),char(0),char(106),char(1), +char(14),char(0),char(107),char(1),char(14),char(0),char(108),char(1),char(14),char(0),char(109),char(1),char(8),char(0),char(110),char(1),char(4),char(0),char(111),char(1), +char(4),char(0),char(86),char(1),char(4),char(0),char(112),char(1),char(4),char(0),char(113),char(1),char(8),char(0),char(114),char(1),char(8),char(0),char(115),char(1), +char(8),char(0),char(116),char(1),char(8),char(0),char(117),char(1),char(8),char(0),char(118),char(1),char(8),char(0),char(119),char(1),char(8),char(0),char(120),char(1), +char(8),char(0),char(121),char(1),char(8),char(0),char(122),char(1),char(0),char(0),char(123),char(1),char(0),char(0),char(124),char(1),char(49),char(0),char(125),char(1), +char(0),char(0),char(126),char(1),char(92),char(0),char(24),char(0),char(15),char(0),char(104),char(1),char(13),char(0),char(105),char(1),char(13),char(0),char(106),char(1), +char(13),char(0),char(107),char(1),char(13),char(0),char(108),char(1),char(13),char(0),char(109),char(1),char(4),char(0),char(112),char(1),char(7),char(0),char(110),char(1), +char(4),char(0),char(111),char(1),char(4),char(0),char(86),char(1),char(7),char(0),char(114),char(1),char(7),char(0),char(115),char(1),char(7),char(0),char(116),char(1), +char(4),char(0),char(113),char(1),char(7),char(0),char(117),char(1),char(7),char(0),char(118),char(1),char(7),char(0),char(119),char(1),char(7),char(0),char(120),char(1), +char(7),char(0),char(121),char(1),char(7),char(0),char(122),char(1),char(0),char(0),char(123),char(1),char(0),char(0),char(124),char(1),char(50),char(0),char(125),char(1), +char(0),char(0),char(126),char(1),char(93),char(0),char(9),char(0),char(20),char(0),char(127),char(1),char(14),char(0),char(-128),char(1),char(8),char(0),char(-127),char(1), +char(0),char(0),char(-126),char(1),char(91),char(0),char(90),char(1),char(49),char(0),char(-125),char(1),char(0),char(0),char(126),char(1),char(4),char(0),char(97),char(1), +char(0),char(0),char(37),char(0),char(94),char(0),char(7),char(0),char(0),char(0),char(-126),char(1),char(92),char(0),char(90),char(1),char(50),char(0),char(-125),char(1), +char(19),char(0),char(127),char(1),char(13),char(0),char(-128),char(1),char(7),char(0),char(-127),char(1),char(4),char(0),char(97),char(1),}; int sBulletDNAlen= sizeof(sBulletDNAstr); diff --git a/extern/bullet/src/LinearMath/btSerializer.h b/extern/bullet/src/LinearMath/btSerializer.h index 39be3f810e49..89b4d7468386 100644 --- a/extern/bullet/src/LinearMath/btSerializer.h +++ b/extern/bullet/src/LinearMath/btSerializer.h @@ -62,8 +62,7 @@ enum btSerializationFlags { BT_SERIALIZE_NO_BVH = 1, BT_SERIALIZE_NO_TRIANGLEINFOMAP = 2, - BT_SERIALIZE_NO_DUPLICATE_ASSERT = 4, - BT_SERIALIZE_CONTACT_MANIFOLDS = 8, + BT_SERIALIZE_NO_DUPLICATE_ASSERT = 4 }; class btSerializer @@ -116,7 +115,6 @@ class btSerializer #define BT_MULTIBODY_CODE BT_MAKE_ID('M','B','D','Y') -#define BT_MB_LINKCOLLIDER_CODE BT_MAKE_ID('M','B','L','C') #define BT_SOFTBODY_CODE BT_MAKE_ID('S','B','D','Y') #define BT_COLLISIONOBJECT_CODE BT_MAKE_ID('C','O','B','J') #define BT_RIGIDBODY_CODE BT_MAKE_ID('R','B','D','Y') @@ -129,9 +127,9 @@ class btSerializer #define BT_SBMATERIAL_CODE BT_MAKE_ID('S','B','M','T') #define BT_SBNODE_CODE BT_MAKE_ID('S','B','N','D') #define BT_DYNAMICSWORLD_CODE BT_MAKE_ID('D','W','L','D') -#define BT_CONTACTMANIFOLD_CODE BT_MAKE_ID('C','O','N','T') #define BT_DNA_CODE BT_MAKE_ID('D','N','A','1') + struct btPointerUid { union @@ -507,7 +505,7 @@ class btDefaultSerializer : public btSerializer buffer[9] = '2'; buffer[10] = '8'; - buffer[11] = '8'; + buffer[11] = '7'; } diff --git a/extern/bullet/src/LinearMath/btSerializer64.cpp b/extern/bullet/src/LinearMath/btSerializer64.cpp index 0aa5cbf30e0b..05f59202d725 100644 --- a/extern/bullet/src/LinearMath/btSerializer64.cpp +++ b/extern/bullet/src/LinearMath/btSerializer64.cpp @@ -1,5 +1,5 @@ char sBulletDNAstr64[]= { -char(83),char(68),char(78),char(65),char(78),char(65),char(77),char(69),char(-76),char(1),char(0),char(0),char(109),char(95),char(115),char(105),char(122),char(101),char(0),char(109), +char(83),char(68),char(78),char(65),char(78),char(65),char(77),char(69),char(-124),char(1),char(0),char(0),char(109),char(95),char(115),char(105),char(122),char(101),char(0),char(109), char(95),char(99),char(97),char(112),char(97),char(99),char(105),char(116),char(121),char(0),char(42),char(109),char(95),char(100),char(97),char(116),char(97),char(0),char(109),char(95), char(99),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(83),char(104),char(97),char(112),char(101),char(115),char(0),char(109),char(95),char(99),char(111), char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(79),char(98),char(106),char(101),char(99),char(116),char(115),char(0),char(109),char(95),char(99),char(111),char(110), @@ -72,618 +72,528 @@ char(105),char(115),char(116),char(97),char(110),char(99),char(101),char(84),cha char(101),char(114),char(111),char(65),char(114),char(101),char(97),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(0),char(109),char(95),char(110), char(101),char(120),char(116),char(83),char(105),char(122),char(101),char(0),char(109),char(95),char(104),char(97),char(115),char(104),char(84),char(97),char(98),char(108),char(101),char(83), char(105),char(122),char(101),char(0),char(109),char(95),char(110),char(117),char(109),char(86),char(97),char(108),char(117),char(101),char(115),char(0),char(109),char(95),char(110),char(117), -char(109),char(75),char(101),char(121),char(115),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(76),char(111), -char(99),char(97),char(108),char(80),char(111),char(105),char(110),char(116),char(65),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116), -char(67),char(97),char(99),char(104),char(101),char(76),char(111),char(99),char(97),char(108),char(80),char(111),char(105),char(110),char(116),char(66),char(91),char(52),char(93),char(0), -char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(80),char(111),char(115),char(105),char(116),char(105),char(111),char(110), -char(87),char(111),char(114),char(108),char(100),char(79),char(110),char(65),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67), -char(97),char(99),char(104),char(101),char(80),char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(87),char(111),char(114),char(108),char(100),char(79),char(110),char(66), -char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(78),char(111),char(114),char(109), -char(97),char(108),char(87),char(111),char(114),char(108),char(100),char(79),char(110),char(66),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110), -char(116),char(67),char(97),char(99),char(104),char(101),char(76),char(97),char(116),char(101),char(114),char(97),char(108),char(70),char(114),char(105),char(99),char(116),char(105),char(111), -char(110),char(68),char(105),char(114),char(49),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104), -char(101),char(76),char(97),char(116),char(101),char(114),char(97),char(108),char(70),char(114),char(105),char(99),char(116),char(105),char(111),char(110),char(68),char(105),char(114),char(50), -char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(68),char(105),char(115),char(116), -char(97),char(110),char(99),char(101),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101), -char(65),char(112),char(112),char(108),char(105),char(101),char(100),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(91),char(52),char(93),char(0),char(109),char(95), -char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(67),char(111),char(109),char(98),char(105),char(110),char(101),char(100),char(70),char(114), -char(105),char(99),char(116),char(105),char(111),char(110),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99), -char(104),char(101),char(67),char(111),char(109),char(98),char(105),char(110),char(101),char(100),char(82),char(111),char(108),char(108),char(105),char(110),char(103),char(70),char(114),char(105), -char(99),char(116),char(105),char(111),char(110),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104), -char(101),char(67),char(111),char(109),char(98),char(105),char(110),char(101),char(100),char(83),char(112),char(105),char(110),char(110),char(105),char(110),char(103),char(70),char(114),char(105), -char(99),char(116),char(105),char(111),char(110),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104), -char(101),char(67),char(111),char(109),char(98),char(105),char(110),char(101),char(100),char(82),char(101),char(115),char(116),char(105),char(116),char(117),char(116),char(105),char(111),char(110), -char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(80),char(97),char(114),char(116), -char(73),char(100),char(48),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(80), -char(97),char(114),char(116),char(73),char(100),char(49),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99), -char(104),char(101),char(73),char(110),char(100),char(101),char(120),char(48),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67), -char(97),char(99),char(104),char(101),char(73),char(110),char(100),char(101),char(120),char(49),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110), -char(116),char(67),char(97),char(99),char(104),char(101),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(80),char(111),char(105),char(110),char(116),char(70),char(108), -char(97),char(103),char(115),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(65), -char(112),char(112),char(108),char(105),char(101),char(100),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(76),char(97),char(116),char(101),char(114),char(97),char(108), -char(49),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(65),char(112),char(112), -char(108),char(105),char(101),char(100),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(76),char(97),char(116),char(101),char(114),char(97),char(108),char(50),char(91), -char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(67),char(111),char(110),char(116),char(97), -char(99),char(116),char(77),char(111),char(116),char(105),char(111),char(110),char(49),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116), -char(67),char(97),char(99),char(104),char(101),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(77),char(111),char(116),char(105),char(111),char(110),char(50),char(91), -char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(67),char(111),char(110),char(116),char(97), -char(99),char(116),char(67),char(70),char(77),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104), -char(101),char(67),char(111),char(109),char(98),char(105),char(110),char(101),char(100),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(83),char(116),char(105),char(102), -char(102),char(110),char(101),char(115),char(115),char(49),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99), -char(104),char(101),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(69),char(82),char(80),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111), -char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(67),char(111),char(109),char(98),char(105),char(110),char(101),char(100),char(67),char(111),char(110),char(116), -char(97),char(99),char(116),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(49),char(91),char(52),char(93),char(0),char(109),char(95),char(112),char(111),char(105), -char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(70),char(114),char(105),char(99),char(116),char(105),char(111),char(110),char(67),char(70),char(77),char(91),char(52), -char(93),char(0),char(109),char(95),char(112),char(111),char(105),char(110),char(116),char(67),char(97),char(99),char(104),char(101),char(76),char(105),char(102),char(101),char(84),char(105), -char(109),char(101),char(91),char(52),char(93),char(0),char(109),char(95),char(110),char(117),char(109),char(67),char(97),char(99),char(104),char(101),char(100),char(80),char(111),char(105), -char(110),char(116),char(115),char(0),char(109),char(95),char(99),char(111),char(109),char(112),char(97),char(110),char(105),char(111),char(110),char(73),char(100),char(65),char(0),char(109), -char(95),char(99),char(111),char(109),char(112),char(97),char(110),char(105),char(111),char(110),char(73),char(100),char(66),char(0),char(109),char(95),char(105),char(110),char(100),char(101), -char(120),char(49),char(97),char(0),char(109),char(95),char(111),char(98),char(106),char(101),char(99),char(116),char(84),char(121),char(112),char(101),char(0),char(109),char(95),char(99), -char(111),char(110),char(116),char(97),char(99),char(116),char(66),char(114),char(101),char(97),char(107),char(105),char(110),char(103),char(84),char(104),char(114),char(101),char(115),char(104), -char(111),char(108),char(100),char(0),char(109),char(95),char(99),char(111),char(110),char(116),char(97),char(99),char(116),char(80),char(114),char(111),char(99),char(101),char(115),char(115), -char(105),char(110),char(103),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(0),char(42),char(109),char(95),char(98),char(111),char(100),char(121), -char(48),char(0),char(42),char(109),char(95),char(98),char(111),char(100),char(121),char(49),char(0),char(109),char(95),char(103),char(105),char(109),char(112),char(97),char(99),char(116), -char(83),char(117),char(98),char(84),char(121),char(112),char(101),char(0),char(42),char(109),char(95),char(117),char(110),char(115),char(99),char(97),char(108),char(101),char(100),char(80), -char(111),char(105),char(110),char(116),char(115),char(70),char(108),char(111),char(97),char(116),char(80),char(116),char(114),char(0),char(42),char(109),char(95),char(117),char(110),char(115), -char(99),char(97),char(108),char(101),char(100),char(80),char(111),char(105),char(110),char(116),char(115),char(68),char(111),char(117),char(98),char(108),char(101),char(80),char(116),char(114), -char(0),char(109),char(95),char(110),char(117),char(109),char(85),char(110),char(115),char(99),char(97),char(108),char(101),char(100),char(80),char(111),char(105),char(110),char(116),char(115), -char(0),char(109),char(95),char(112),char(97),char(100),char(100),char(105),char(110),char(103),char(51),char(91),char(52),char(93),char(0),char(42),char(109),char(95),char(98),char(114), -char(111),char(97),char(100),char(112),char(104),char(97),char(115),char(101),char(72),char(97),char(110),char(100),char(108),char(101),char(0),char(42),char(109),char(95),char(99),char(111), -char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(83),char(104),char(97),char(112),char(101),char(0),char(42),char(109),char(95),char(114),char(111),char(111),char(116), -char(67),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(83),char(104),char(97),char(112),char(101),char(0),char(109),char(95),char(119),char(111),char(114), -char(108),char(100),char(84),char(114),char(97),char(110),char(115),char(102),char(111),char(114),char(109),char(0),char(109),char(95),char(105),char(110),char(116),char(101),char(114),char(112), -char(111),char(108),char(97),char(116),char(105),char(111),char(110),char(87),char(111),char(114),char(108),char(100),char(84),char(114),char(97),char(110),char(115),char(102),char(111),char(114), -char(109),char(0),char(109),char(95),char(105),char(110),char(116),char(101),char(114),char(112),char(111),char(108),char(97),char(116),char(105),char(111),char(110),char(76),char(105),char(110), -char(101),char(97),char(114),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109),char(95),char(105),char(110),char(116),char(101),char(114),char(112), -char(111),char(108),char(97),char(116),char(105),char(111),char(110),char(65),char(110),char(103),char(117),char(108),char(97),char(114),char(86),char(101),char(108),char(111),char(99),char(105), -char(116),char(121),char(0),char(109),char(95),char(97),char(110),char(105),char(115),char(111),char(116),char(114),char(111),char(112),char(105),char(99),char(70),char(114),char(105),char(99), -char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(100),char(101),char(97),char(99),char(116),char(105),char(118),char(97),char(116),char(105),char(111),char(110),char(84), -char(105),char(109),char(101),char(0),char(109),char(95),char(102),char(114),char(105),char(99),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(114),char(111),char(108), -char(108),char(105),char(110),char(103),char(70),char(114),char(105),char(99),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(99),char(111),char(110),char(116),char(97), -char(99),char(116),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(0),char(109),char(95),char(99),char(111),char(110),char(116),char(97),char(99),char(116),char(83), -char(116),char(105),char(102),char(102),char(110),char(101),char(115),char(115),char(0),char(109),char(95),char(114),char(101),char(115),char(116),char(105),char(116),char(117),char(116),char(105), -char(111),char(110),char(0),char(109),char(95),char(104),char(105),char(116),char(70),char(114),char(97),char(99),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(99), -char(99),char(100),char(83),char(119),char(101),char(112),char(116),char(83),char(112),char(104),char(101),char(114),char(101),char(82),char(97),char(100),char(105),char(117),char(115),char(0), -char(109),char(95),char(99),char(99),char(100),char(77),char(111),char(116),char(105),char(111),char(110),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100), -char(0),char(109),char(95),char(104),char(97),char(115),char(65),char(110),char(105),char(115),char(111),char(116),char(114),char(111),char(112),char(105),char(99),char(70),char(114),char(105), -char(99),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(99),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(70),char(108),char(97), -char(103),char(115),char(0),char(109),char(95),char(105),char(115),char(108),char(97),char(110),char(100),char(84),char(97),char(103),char(49),char(0),char(109),char(95),char(99),char(111), -char(109),char(112),char(97),char(110),char(105),char(111),char(110),char(73),char(100),char(0),char(109),char(95),char(97),char(99),char(116),char(105),char(118),char(97),char(116),char(105), -char(111),char(110),char(83),char(116),char(97),char(116),char(101),char(49),char(0),char(109),char(95),char(105),char(110),char(116),char(101),char(114),char(110),char(97),char(108),char(84), -char(121),char(112),char(101),char(0),char(109),char(95),char(99),char(104),char(101),char(99),char(107),char(67),char(111),char(108),char(108),char(105),char(100),char(101),char(87),char(105), -char(116),char(104),char(0),char(109),char(95),char(99),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(70),char(105),char(108),char(116),char(101),char(114), -char(71),char(114),char(111),char(117),char(112),char(0),char(109),char(95),char(99),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(70),char(105),char(108), -char(116),char(101),char(114),char(77),char(97),char(115),char(107),char(0),char(109),char(95),char(117),char(110),char(105),char(113),char(117),char(101),char(73),char(100),char(0),char(109), -char(95),char(116),char(97),char(117),char(0),char(109),char(95),char(100),char(97),char(109),char(112),char(105),char(110),char(103),char(0),char(109),char(95),char(116),char(105),char(109), -char(101),char(83),char(116),char(101),char(112),char(0),char(109),char(95),char(109),char(97),char(120),char(69),char(114),char(114),char(111),char(114),char(82),char(101),char(100),char(117), -char(99),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(115),char(111),char(114),char(0),char(109),char(95),char(101),char(114),char(112),char(0),char(109),char(95), -char(101),char(114),char(112),char(50),char(0),char(109),char(95),char(103),char(108),char(111),char(98),char(97),char(108),char(67),char(102),char(109),char(0),char(109),char(95),char(115), -char(112),char(108),char(105),char(116),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(80),char(101),char(110),char(101),char(116),char(114),char(97),char(116),char(105), -char(111),char(110),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(0),char(109),char(95),char(115),char(112),char(108),char(105),char(116),char(73), -char(109),char(112),char(117),char(108),char(115),char(101),char(84),char(117),char(114),char(110),char(69),char(114),char(112),char(0),char(109),char(95),char(108),char(105),char(110),char(101), -char(97),char(114),char(83),char(108),char(111),char(112),char(0),char(109),char(95),char(119),char(97),char(114),char(109),char(115),char(116),char(97),char(114),char(116),char(105),char(110), -char(103),char(70),char(97),char(99),char(116),char(111),char(114),char(0),char(109),char(95),char(109),char(97),char(120),char(71),char(121),char(114),char(111),char(115),char(99),char(111), -char(112),char(105),char(99),char(70),char(111),char(114),char(99),char(101),char(0),char(109),char(95),char(115),char(105),char(110),char(103),char(108),char(101),char(65),char(120),char(105), -char(115),char(82),char(111),char(108),char(108),char(105),char(110),char(103),char(70),char(114),char(105),char(99),char(116),char(105),char(111),char(110),char(84),char(104),char(114),char(101), -char(115),char(104),char(111),char(108),char(100),char(0),char(109),char(95),char(110),char(117),char(109),char(73),char(116),char(101),char(114),char(97),char(116),char(105),char(111),char(110), -char(115),char(0),char(109),char(95),char(115),char(111),char(108),char(118),char(101),char(114),char(77),char(111),char(100),char(101),char(0),char(109),char(95),char(114),char(101),char(115), -char(116),char(105),char(110),char(103),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(82),char(101),char(115),char(116),char(105),char(116),char(117),char(116),char(105), -char(111),char(110),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(0),char(109),char(95),char(109),char(105),char(110),char(105),char(109),char(117), -char(109),char(83),char(111),char(108),char(118),char(101),char(114),char(66),char(97),char(116),char(99),char(104),char(83),char(105),char(122),char(101),char(0),char(109),char(95),char(115), -char(112),char(108),char(105),char(116),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(0),char(109),char(95),char(115),char(111),char(108),char(118),char(101),char(114), -char(73),char(110),char(102),char(111),char(0),char(109),char(95),char(103),char(114),char(97),char(118),char(105),char(116),char(121),char(0),char(109),char(95),char(99),char(111),char(108), -char(108),char(105),char(115),char(105),char(111),char(110),char(79),char(98),char(106),char(101),char(99),char(116),char(68),char(97),char(116),char(97),char(0),char(109),char(95),char(105), -char(110),char(118),char(73),char(110),char(101),char(114),char(116),char(105),char(97),char(84),char(101),char(110),char(115),char(111),char(114),char(87),char(111),char(114),char(108),char(100), -char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109),char(95), -char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109),char(95),char(97),char(110), -char(103),char(117),char(108),char(97),char(114),char(70),char(97),char(99),char(116),char(111),char(114),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114), -char(70),char(97),char(99),char(116),char(111),char(114),char(0),char(109),char(95),char(103),char(114),char(97),char(118),char(105),char(116),char(121),char(95),char(97),char(99),char(99), -char(101),char(108),char(101),char(114),char(97),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(105),char(110),char(118),char(73),char(110),char(101),char(114),char(116), -char(105),char(97),char(76),char(111),char(99),char(97),char(108),char(0),char(109),char(95),char(116),char(111),char(116),char(97),char(108),char(70),char(111),char(114),char(99),char(101), -char(0),char(109),char(95),char(116),char(111),char(116),char(97),char(108),char(84),char(111),char(114),char(113),char(117),char(101),char(0),char(109),char(95),char(105),char(110),char(118), -char(101),char(114),char(115),char(101),char(77),char(97),char(115),char(115),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(68),char(97),char(109), -char(112),char(105),char(110),char(103),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(68),char(97),char(109),char(112),char(105),char(110), -char(103),char(0),char(109),char(95),char(97),char(100),char(100),char(105),char(116),char(105),char(111),char(110),char(97),char(108),char(68),char(97),char(109),char(112),char(105),char(110), -char(103),char(70),char(97),char(99),char(116),char(111),char(114),char(0),char(109),char(95),char(97),char(100),char(100),char(105),char(116),char(105),char(111),char(110),char(97),char(108), -char(76),char(105),char(110),char(101),char(97),char(114),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(84),char(104),char(114),char(101),char(115),char(104),char(111), -char(108),char(100),char(83),char(113),char(114),char(0),char(109),char(95),char(97),char(100),char(100),char(105),char(116),char(105),char(111),char(110),char(97),char(108),char(65),char(110), -char(103),char(117),char(108),char(97),char(114),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108), -char(100),char(83),char(113),char(114),char(0),char(109),char(95),char(97),char(100),char(100),char(105),char(116),char(105),char(111),char(110),char(97),char(108),char(65),char(110),char(103), -char(117),char(108),char(97),char(114),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(70),char(97),char(99),char(116),char(111),char(114),char(0),char(109),char(95), -char(108),char(105),char(110),char(101),char(97),char(114),char(83),char(108),char(101),char(101),char(112),char(105),char(110),char(103),char(84),char(104),char(114),char(101),char(115),char(104), -char(111),char(108),char(100),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(83),char(108),char(101),char(101),char(112),char(105),char(110), -char(103),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(0),char(109),char(95),char(97),char(100),char(100),char(105),char(116),char(105),char(111), -char(110),char(97),char(108),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(0),char(109),char(95),char(110),char(117),char(109),char(67),char(111),char(110),char(115), -char(116),char(114),char(97),char(105),char(110),char(116),char(82),char(111),char(119),char(115),char(0),char(110),char(117),char(98),char(0),char(42),char(109),char(95),char(114),char(98), -char(65),char(0),char(42),char(109),char(95),char(114),char(98),char(66),char(0),char(109),char(95),char(117),char(115),char(101),char(114),char(67),char(111),char(110),char(115),char(116), -char(114),char(97),char(105),char(110),char(116),char(84),char(121),char(112),char(101),char(0),char(109),char(95),char(117),char(115),char(101),char(114),char(67),char(111),char(110),char(115), -char(116),char(114),char(97),char(105),char(110),char(116),char(73),char(100),char(0),char(109),char(95),char(110),char(101),char(101),char(100),char(115),char(70),char(101),char(101),char(100), -char(98),char(97),char(99),char(107),char(0),char(109),char(95),char(97),char(112),char(112),char(108),char(105),char(101),char(100),char(73),char(109),char(112),char(117),char(108),char(115), -char(101),char(0),char(109),char(95),char(100),char(98),char(103),char(68),char(114),char(97),char(119),char(83),char(105),char(122),char(101),char(0),char(109),char(95),char(100),char(105), -char(115),char(97),char(98),char(108),char(101),char(67),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(115),char(66),char(101),char(116),char(119),char(101), -char(101),char(110),char(76),char(105),char(110),char(107),char(101),char(100),char(66),char(111),char(100),char(105),char(101),char(115),char(0),char(109),char(95),char(111),char(118),char(101), -char(114),char(114),char(105),char(100),char(101),char(78),char(117),char(109),char(83),char(111),char(108),char(118),char(101),char(114),char(73),char(116),char(101),char(114),char(97),char(116), -char(105),char(111),char(110),char(115),char(0),char(109),char(95),char(98),char(114),char(101),char(97),char(107),char(105),char(110),char(103),char(73),char(109),char(112),char(117),char(108), -char(115),char(101),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(0),char(109),char(95),char(105),char(115),char(69),char(110),char(97),char(98), -char(108),char(101),char(100),char(0),char(112),char(97),char(100),char(100),char(105),char(110),char(103),char(91),char(52),char(93),char(0),char(109),char(95),char(116),char(121),char(112), -char(101),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(109),char(95),char(112),char(105), -char(118),char(111),char(116),char(73),char(110),char(65),char(0),char(109),char(95),char(112),char(105),char(118),char(111),char(116),char(73),char(110),char(66),char(0),char(109),char(95), -char(114),char(98),char(65),char(70),char(114),char(97),char(109),char(101),char(0),char(109),char(95),char(114),char(98),char(66),char(70),char(114),char(97),char(109),char(101),char(0), -char(109),char(95),char(117),char(115),char(101),char(82),char(101),char(102),char(101),char(114),char(101),char(110),char(99),char(101),char(70),char(114),char(97),char(109),char(101),char(65), -char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(79),char(110),char(108),char(121),char(0),char(109),char(95),char(101),char(110),char(97), -char(98),char(108),char(101),char(65),char(110),char(103),char(117),char(108),char(97),char(114),char(77),char(111),char(116),char(111),char(114),char(0),char(109),char(95),char(109),char(111), -char(116),char(111),char(114),char(84),char(97),char(114),char(103),char(101),char(116),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109),char(95), -char(109),char(97),char(120),char(77),char(111),char(116),char(111),char(114),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(0),char(109),char(95),char(108),char(111), -char(119),char(101),char(114),char(76),char(105),char(109),char(105),char(116),char(0),char(109),char(95),char(117),char(112),char(112),char(101),char(114),char(76),char(105),char(109),char(105), -char(116),char(0),char(109),char(95),char(108),char(105),char(109),char(105),char(116),char(83),char(111),char(102),char(116),char(110),char(101),char(115),char(115),char(0),char(109),char(95), -char(98),char(105),char(97),char(115),char(70),char(97),char(99),char(116),char(111),char(114),char(0),char(109),char(95),char(114),char(101),char(108),char(97),char(120),char(97),char(116), -char(105),char(111),char(110),char(70),char(97),char(99),char(116),char(111),char(114),char(0),char(109),char(95),char(112),char(97),char(100),char(100),char(105),char(110),char(103),char(49), -char(91),char(52),char(93),char(0),char(109),char(95),char(115),char(119),char(105),char(110),char(103),char(83),char(112),char(97),char(110),char(49),char(0),char(109),char(95),char(115), -char(119),char(105),char(110),char(103),char(83),char(112),char(97),char(110),char(50),char(0),char(109),char(95),char(116),char(119),char(105),char(115),char(116),char(83),char(112),char(97), -char(110),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(85),char(112),char(112),char(101),char(114),char(76),char(105),char(109),char(105),char(116), -char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(76),char(111),char(119),char(101),char(114),char(76),char(105),char(109),char(105),char(116),char(0), -char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(85),char(112),char(112),char(101),char(114),char(76),char(105),char(109),char(105),char(116),char(0), -char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(76),char(111),char(119),char(101),char(114),char(76),char(105),char(109),char(105),char(116),char(0), -char(109),char(95),char(117),char(115),char(101),char(76),char(105),char(110),char(101),char(97),char(114),char(82),char(101),char(102),char(101),char(114),char(101),char(110),char(99),char(101), -char(70),char(114),char(97),char(109),char(101),char(65),char(0),char(109),char(95),char(117),char(115),char(101),char(79),char(102),char(102),char(115),char(101),char(116),char(70),char(111), -char(114),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(114),char(97),char(109),char(101),char(0),char(109),char(95),char(54), -char(100),char(111),char(102),char(68),char(97),char(116),char(97),char(0),char(109),char(95),char(115),char(112),char(114),char(105),char(110),char(103),char(69),char(110),char(97),char(98), -char(108),char(101),char(100),char(91),char(54),char(93),char(0),char(109),char(95),char(101),char(113),char(117),char(105),char(108),char(105),char(98),char(114),char(105),char(117),char(109), -char(80),char(111),char(105),char(110),char(116),char(91),char(54),char(93),char(0),char(109),char(95),char(115),char(112),char(114),char(105),char(110),char(103),char(83),char(116),char(105), -char(102),char(102),char(110),char(101),char(115),char(115),char(91),char(54),char(93),char(0),char(109),char(95),char(115),char(112),char(114),char(105),char(110),char(103),char(68),char(97), -char(109),char(112),char(105),char(110),char(103),char(91),char(54),char(93),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(66),char(111),char(117), -char(110),char(99),char(101),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(83),char(116),char(111),char(112),char(69),char(82),char(80),char(0), -char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(83),char(116),char(111),char(112),char(67),char(70),char(77),char(0),char(109),char(95),char(108),char(105), -char(110),char(101),char(97),char(114),char(77),char(111),char(116),char(111),char(114),char(69),char(82),char(80),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97), -char(114),char(77),char(111),char(116),char(111),char(114),char(67),char(70),char(77),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(84),char(97), -char(114),char(103),char(101),char(116),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97), -char(114),char(77),char(97),char(120),char(77),char(111),char(116),char(111),char(114),char(70),char(111),char(114),char(99),char(101),char(0),char(109),char(95),char(108),char(105),char(110), -char(101),char(97),char(114),char(83),char(101),char(114),char(118),char(111),char(84),char(97),char(114),char(103),char(101),char(116),char(0),char(109),char(95),char(108),char(105),char(110), -char(101),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(83),char(116),char(105),char(102),char(102),char(110),char(101),char(115),char(115),char(0),char(109), -char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(68),char(97),char(109),char(112),char(105),char(110),char(103), -char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(69),char(113),char(117),char(105),char(108),char(105),char(98),char(114),char(105),char(117),char(109), -char(80),char(111),char(105),char(110),char(116),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(69),char(110),char(97),char(98),char(108),char(101), -char(77),char(111),char(116),char(111),char(114),char(91),char(52),char(93),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(83),char(101),char(114), -char(118),char(111),char(77),char(111),char(116),char(111),char(114),char(91),char(52),char(93),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(69), -char(110),char(97),char(98),char(108),char(101),char(83),char(112),char(114),char(105),char(110),char(103),char(91),char(52),char(93),char(0),char(109),char(95),char(108),char(105),char(110), -char(101),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(83),char(116),char(105),char(102),char(102),char(110),char(101),char(115),char(115),char(76),char(105), -char(109),char(105),char(116),char(101),char(100),char(91),char(52),char(93),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(83),char(112),char(114), -char(105),char(110),char(103),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(76),char(105),char(109),char(105),char(116),char(101),char(100),char(91),char(52),char(93), -char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(66),char(111),char(117),char(110),char(99),char(101),char(0),char(109),char(95),char(97), -char(110),char(103),char(117),char(108),char(97),char(114),char(83),char(116),char(111),char(112),char(69),char(82),char(80),char(0),char(109),char(95),char(97),char(110),char(103),char(117), -char(108),char(97),char(114),char(83),char(116),char(111),char(112),char(67),char(70),char(77),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114), -char(77),char(111),char(116),char(111),char(114),char(69),char(82),char(80),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(77),char(111), -char(116),char(111),char(114),char(67),char(70),char(77),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(84),char(97),char(114),char(103), -char(101),char(116),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114), -char(77),char(97),char(120),char(77),char(111),char(116),char(111),char(114),char(70),char(111),char(114),char(99),char(101),char(0),char(109),char(95),char(97),char(110),char(103),char(117), -char(108),char(97),char(114),char(83),char(101),char(114),char(118),char(111),char(84),char(97),char(114),char(103),char(101),char(116),char(0),char(109),char(95),char(97),char(110),char(103), -char(117),char(108),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(83),char(116),char(105),char(102),char(102),char(110),char(101),char(115),char(115),char(0), -char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(68),char(97),char(109),char(112),char(105), -char(110),char(103),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(69),char(113),char(117),char(105),char(108),char(105),char(98),char(114), -char(105),char(117),char(109),char(80),char(111),char(105),char(110),char(116),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(69),char(110), -char(97),char(98),char(108),char(101),char(77),char(111),char(116),char(111),char(114),char(91),char(52),char(93),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108), -char(97),char(114),char(83),char(101),char(114),char(118),char(111),char(77),char(111),char(116),char(111),char(114),char(91),char(52),char(93),char(0),char(109),char(95),char(97),char(110), -char(103),char(117),char(108),char(97),char(114),char(69),char(110),char(97),char(98),char(108),char(101),char(83),char(112),char(114),char(105),char(110),char(103),char(91),char(52),char(93), -char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(83),char(116),char(105),char(102), -char(102),char(110),char(101),char(115),char(115),char(76),char(105),char(109),char(105),char(116),char(101),char(100),char(91),char(52),char(93),char(0),char(109),char(95),char(97),char(110), -char(103),char(117),char(108),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(76),char(105), -char(109),char(105),char(116),char(101),char(100),char(91),char(52),char(93),char(0),char(109),char(95),char(114),char(111),char(116),char(97),char(116),char(101),char(79),char(114),char(100), -char(101),char(114),char(0),char(109),char(95),char(97),char(120),char(105),char(115),char(73),char(110),char(65),char(0),char(109),char(95),char(97),char(120),char(105),char(115),char(73), -char(110),char(66),char(0),char(109),char(95),char(114),char(97),char(116),char(105),char(111),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(83), -char(116),char(105),char(102),char(102),char(110),char(101),char(115),char(115),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(83),char(116), -char(105),char(102),char(102),char(110),char(101),char(115),char(115),char(0),char(109),char(95),char(118),char(111),char(108),char(117),char(109),char(101),char(83),char(116),char(105),char(102), -char(102),char(110),char(101),char(115),char(115),char(0),char(42),char(109),char(95),char(109),char(97),char(116),char(101),char(114),char(105),char(97),char(108),char(0),char(109),char(95), -char(112),char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(112),char(114),char(101),char(118),char(105),char(111),char(117),char(115),char(80), -char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(118),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109), -char(95),char(97),char(99),char(99),char(117),char(109),char(117),char(108),char(97),char(116),char(101),char(100),char(70),char(111),char(114),char(99),char(101),char(0),char(109),char(95), -char(110),char(111),char(114),char(109),char(97),char(108),char(0),char(109),char(95),char(97),char(114),char(101),char(97),char(0),char(109),char(95),char(97),char(116),char(116),char(97), -char(99),char(104),char(0),char(109),char(95),char(110),char(111),char(100),char(101),char(73),char(110),char(100),char(105),char(99),char(101),char(115),char(91),char(50),char(93),char(0), -char(109),char(95),char(114),char(101),char(115),char(116),char(76),char(101),char(110),char(103),char(116),char(104),char(0),char(109),char(95),char(98),char(98),char(101),char(110),char(100), -char(105),char(110),char(103),char(0),char(109),char(95),char(110),char(111),char(100),char(101),char(73),char(110),char(100),char(105),char(99),char(101),char(115),char(91),char(51),char(93), -char(0),char(109),char(95),char(114),char(101),char(115),char(116),char(65),char(114),char(101),char(97),char(0),char(109),char(95),char(99),char(48),char(91),char(52),char(93),char(0), -char(109),char(95),char(110),char(111),char(100),char(101),char(73),char(110),char(100),char(105),char(99),char(101),char(115),char(91),char(52),char(93),char(0),char(109),char(95),char(114), -char(101),char(115),char(116),char(86),char(111),char(108),char(117),char(109),char(101),char(0),char(109),char(95),char(99),char(49),char(0),char(109),char(95),char(99),char(50),char(0), -char(109),char(95),char(99),char(48),char(0),char(109),char(95),char(108),char(111),char(99),char(97),char(108),char(70),char(114),char(97),char(109),char(101),char(0),char(42),char(109), -char(95),char(114),char(105),char(103),char(105),char(100),char(66),char(111),char(100),char(121),char(0),char(109),char(95),char(110),char(111),char(100),char(101),char(73),char(110),char(100), -char(101),char(120),char(0),char(109),char(95),char(97),char(101),char(114),char(111),char(77),char(111),char(100),char(101),char(108),char(0),char(109),char(95),char(98),char(97),char(117), -char(109),char(103),char(97),char(114),char(116),char(101),char(0),char(109),char(95),char(100),char(114),char(97),char(103),char(0),char(109),char(95),char(108),char(105),char(102),char(116), -char(0),char(109),char(95),char(112),char(114),char(101),char(115),char(115),char(117),char(114),char(101),char(0),char(109),char(95),char(118),char(111),char(108),char(117),char(109),char(101), -char(0),char(109),char(95),char(100),char(121),char(110),char(97),char(109),char(105),char(99),char(70),char(114),char(105),char(99),char(116),char(105),char(111),char(110),char(0),char(109), -char(95),char(112),char(111),char(115),char(101),char(77),char(97),char(116),char(99),char(104),char(0),char(109),char(95),char(114),char(105),char(103),char(105),char(100),char(67),char(111), -char(110),char(116),char(97),char(99),char(116),char(72),char(97),char(114),char(100),char(110),char(101),char(115),char(115),char(0),char(109),char(95),char(107),char(105),char(110),char(101), -char(116),char(105),char(99),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(72),char(97),char(114),char(100),char(110),char(101),char(115),char(115),char(0),char(109), -char(95),char(115),char(111),char(102),char(116),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(72),char(97),char(114),char(100),char(110),char(101),char(115),char(115), -char(0),char(109),char(95),char(97),char(110),char(99),char(104),char(111),char(114),char(72),char(97),char(114),char(100),char(110),char(101),char(115),char(115),char(0),char(109),char(95), -char(115),char(111),char(102),char(116),char(82),char(105),char(103),char(105),char(100),char(67),char(108),char(117),char(115),char(116),char(101),char(114),char(72),char(97),char(114),char(100), -char(110),char(101),char(115),char(115),char(0),char(109),char(95),char(115),char(111),char(102),char(116),char(75),char(105),char(110),char(101),char(116),char(105),char(99),char(67),char(108), -char(117),char(115),char(116),char(101),char(114),char(72),char(97),char(114),char(100),char(110),char(101),char(115),char(115),char(0),char(109),char(95),char(115),char(111),char(102),char(116), -char(83),char(111),char(102),char(116),char(67),char(108),char(117),char(115),char(116),char(101),char(114),char(72),char(97),char(114),char(100),char(110),char(101),char(115),char(115),char(0), -char(109),char(95),char(115),char(111),char(102),char(116),char(82),char(105),char(103),char(105),char(100),char(67),char(108),char(117),char(115),char(116),char(101),char(114),char(73),char(109), -char(112),char(117),char(108),char(115),char(101),char(83),char(112),char(108),char(105),char(116),char(0),char(109),char(95),char(115),char(111),char(102),char(116),char(75),char(105),char(110), -char(101),char(116),char(105),char(99),char(67),char(108),char(117),char(115),char(116),char(101),char(114),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(83),char(112), -char(108),char(105),char(116),char(0),char(109),char(95),char(115),char(111),char(102),char(116),char(83),char(111),char(102),char(116),char(67),char(108),char(117),char(115),char(116),char(101), -char(114),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(83),char(112),char(108),char(105),char(116),char(0),char(109),char(95),char(109),char(97),char(120),char(86), -char(111),char(108),char(117),char(109),char(101),char(0),char(109),char(95),char(116),char(105),char(109),char(101),char(83),char(99),char(97),char(108),char(101),char(0),char(109),char(95), -char(118),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(73),char(116),char(101),char(114),char(97),char(116),char(105),char(111),char(110),char(115),char(0),char(109), -char(95),char(112),char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(73),char(116),char(101),char(114),char(97),char(116),char(105),char(111),char(110),char(115),char(0), -char(109),char(95),char(100),char(114),char(105),char(102),char(116),char(73),char(116),char(101),char(114),char(97),char(116),char(105),char(111),char(110),char(115),char(0),char(109),char(95), -char(99),char(108),char(117),char(115),char(116),char(101),char(114),char(73),char(116),char(101),char(114),char(97),char(116),char(105),char(111),char(110),char(115),char(0),char(109),char(95), -char(114),char(111),char(116),char(0),char(109),char(95),char(115),char(99),char(97),char(108),char(101),char(0),char(109),char(95),char(97),char(113),char(113),char(0),char(109),char(95), -char(99),char(111),char(109),char(0),char(42),char(109),char(95),char(112),char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(115),char(0),char(42),char(109),char(95), -char(119),char(101),char(105),char(103),char(104),char(116),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(80),char(111),char(115),char(105),char(116),char(105),char(111), -char(110),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(87),char(101),char(105),char(103),char(116),char(115),char(0),char(109),char(95),char(98),char(118),char(111), -char(108),char(117),char(109),char(101),char(0),char(109),char(95),char(98),char(102),char(114),char(97),char(109),char(101),char(0),char(109),char(95),char(102),char(114),char(97),char(109), -char(101),char(120),char(102),char(111),char(114),char(109),char(0),char(109),char(95),char(108),char(111),char(99),char(105),char(105),char(0),char(109),char(95),char(105),char(110),char(118), -char(119),char(105),char(0),char(109),char(95),char(118),char(105),char(109),char(112),char(117),char(108),char(115),char(101),char(115),char(91),char(50),char(93),char(0),char(109),char(95), -char(100),char(105),char(109),char(112),char(117),char(108),char(115),char(101),char(115),char(91),char(50),char(93),char(0),char(109),char(95),char(108),char(118),char(0),char(109),char(95), -char(97),char(118),char(0),char(42),char(109),char(95),char(102),char(114),char(97),char(109),char(101),char(114),char(101),char(102),char(115),char(0),char(42),char(109),char(95),char(110), -char(111),char(100),char(101),char(73),char(110),char(100),char(105),char(99),char(101),char(115),char(0),char(42),char(109),char(95),char(109),char(97),char(115),char(115),char(101),char(115), -char(0),char(109),char(95),char(110),char(117),char(109),char(70),char(114),char(97),char(109),char(101),char(82),char(101),char(102),char(115),char(0),char(109),char(95),char(110),char(117), -char(109),char(78),char(111),char(100),char(101),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(77),char(97),char(115),char(115),char(101),char(115),char(0),char(109), -char(95),char(105),char(100),char(109),char(97),char(115),char(115),char(0),char(109),char(95),char(105),char(109),char(97),char(115),char(115),char(0),char(109),char(95),char(110),char(118), -char(105),char(109),char(112),char(117),char(108),char(115),char(101),char(115),char(0),char(109),char(95),char(110),char(100),char(105),char(109),char(112),char(117),char(108),char(115),char(101), -char(115),char(0),char(109),char(95),char(110),char(100),char(97),char(109),char(112),char(105),char(110),char(103),char(0),char(109),char(95),char(108),char(100),char(97),char(109),char(112), -char(105),char(110),char(103),char(0),char(109),char(95),char(97),char(100),char(97),char(109),char(112),char(105),char(110),char(103),char(0),char(109),char(95),char(109),char(97),char(116), -char(99),char(104),char(105),char(110),char(103),char(0),char(109),char(95),char(109),char(97),char(120),char(83),char(101),char(108),char(102),char(67),char(111),char(108),char(108),char(105), -char(115),char(105),char(111),char(110),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(0),char(109),char(95),char(115),char(101),char(108),char(102),char(67),char(111), -char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(70),char(97),char(99),char(116),char(111),char(114), -char(0),char(109),char(95),char(99),char(111),char(110),char(116),char(97),char(105),char(110),char(115),char(65),char(110),char(99),char(104),char(111),char(114),char(0),char(109),char(95), -char(99),char(111),char(108),char(108),char(105),char(100),char(101),char(0),char(109),char(95),char(99),char(108),char(117),char(115),char(116),char(101),char(114),char(73),char(110),char(100), -char(101),char(120),char(0),char(42),char(109),char(95),char(98),char(111),char(100),char(121),char(65),char(0),char(42),char(109),char(95),char(98),char(111),char(100),char(121),char(66), -char(0),char(109),char(95),char(114),char(101),char(102),char(115),char(91),char(50),char(93),char(0),char(109),char(95),char(99),char(102),char(109),char(0),char(109),char(95),char(115), -char(112),char(108),char(105),char(116),char(0),char(109),char(95),char(100),char(101),char(108),char(101),char(116),char(101),char(0),char(109),char(95),char(114),char(101),char(108),char(80), -char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(91),char(50),char(93),char(0),char(109),char(95),char(98),char(111),char(100),char(121),char(65),char(116),char(121), -char(112),char(101),char(0),char(109),char(95),char(98),char(111),char(100),char(121),char(66),char(116),char(121),char(112),char(101),char(0),char(109),char(95),char(106),char(111),char(105), -char(110),char(116),char(84),char(121),char(112),char(101),char(0),char(42),char(109),char(95),char(112),char(111),char(115),char(101),char(0),char(42),char(42),char(109),char(95),char(109), -char(97),char(116),char(101),char(114),char(105),char(97),char(108),char(115),char(0),char(42),char(109),char(95),char(110),char(111),char(100),char(101),char(115),char(0),char(42),char(109), -char(95),char(108),char(105),char(110),char(107),char(115),char(0),char(42),char(109),char(95),char(102),char(97),char(99),char(101),char(115),char(0),char(42),char(109),char(95),char(116), -char(101),char(116),char(114),char(97),char(104),char(101),char(100),char(114),char(97),char(0),char(42),char(109),char(95),char(97),char(110),char(99),char(104),char(111),char(114),char(115), -char(0),char(42),char(109),char(95),char(99),char(108),char(117),char(115),char(116),char(101),char(114),char(115),char(0),char(42),char(109),char(95),char(106),char(111),char(105),char(110), -char(116),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(77),char(97),char(116),char(101),char(114),char(105),char(97),char(108),char(115),char(0),char(109),char(95), -char(110),char(117),char(109),char(76),char(105),char(110),char(107),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(70),char(97),char(99),char(101),char(115),char(0), -char(109),char(95),char(110),char(117),char(109),char(84),char(101),char(116),char(114),char(97),char(104),char(101),char(100),char(114),char(97),char(0),char(109),char(95),char(110),char(117), -char(109),char(65),char(110),char(99),char(104),char(111),char(114),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(67),char(108),char(117),char(115),char(116),char(101), -char(114),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(74),char(111),char(105),char(110),char(116),char(115),char(0),char(109),char(95),char(99),char(111),char(110), -char(102),char(105),char(103),char(0),char(109),char(95),char(122),char(101),char(114),char(111),char(82),char(111),char(116),char(80),char(97),char(114),char(101),char(110),char(116),char(84), -char(111),char(84),char(104),char(105),char(115),char(0),char(109),char(95),char(112),char(97),char(114),char(101),char(110),char(116),char(67),char(111),char(109),char(84),char(111),char(84), -char(104),char(105),char(115),char(80),char(105),char(118),char(111),char(116),char(79),char(102),char(102),char(115),char(101),char(116),char(0),char(109),char(95),char(116),char(104),char(105), -char(115),char(80),char(105),char(118),char(111),char(116),char(84),char(111),char(84),char(104),char(105),char(115),char(67),char(111),char(109),char(79),char(102),char(102),char(115),char(101), -char(116),char(0),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(65),char(120),char(105),char(115),char(84),char(111),char(112),char(91),char(54),char(93),char(0), -char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(65),char(120),char(105),char(115),char(66),char(111),char(116),char(116),char(111),char(109),char(91),char(54),char(93), -char(0),char(109),char(95),char(108),char(105),char(110),char(107),char(73),char(110),char(101),char(114),char(116),char(105),char(97),char(0),char(109),char(95),char(97),char(98),char(115), -char(70),char(114),char(97),char(109),char(101),char(84),char(111),char(116),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(84),char(111),char(112),char(0), -char(109),char(95),char(97),char(98),char(115),char(70),char(114),char(97),char(109),char(101),char(84),char(111),char(116),char(86),char(101),char(108),char(111),char(99),char(105),char(116), -char(121),char(66),char(111),char(116),char(116),char(111),char(109),char(0),char(109),char(95),char(97),char(98),char(115),char(70),char(114),char(97),char(109),char(101),char(76),char(111), -char(99),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(84),char(111),char(112),char(0),char(109),char(95),char(97),char(98),char(115),char(70),char(114), -char(97),char(109),char(101),char(76),char(111),char(99),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(66),char(111),char(116),char(116),char(111),char(109), -char(0),char(109),char(95),char(108),char(105),char(110),char(107),char(77),char(97),char(115),char(115),char(0),char(109),char(95),char(112),char(97),char(114),char(101),char(110),char(116), -char(73),char(110),char(100),char(101),char(120),char(0),char(109),char(95),char(100),char(111),char(102),char(67),char(111),char(117),char(110),char(116),char(0),char(109),char(95),char(112), -char(111),char(115),char(86),char(97),char(114),char(67),char(111),char(117),char(110),char(116),char(0),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(80),char(111), -char(115),char(91),char(55),char(93),char(0),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(86),char(101),char(108),char(91),char(54),char(93),char(0),char(109), -char(95),char(106),char(111),char(105),char(110),char(116),char(84),char(111),char(114),char(113),char(117),char(101),char(91),char(54),char(93),char(0),char(109),char(95),char(106),char(111), -char(105),char(110),char(116),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(0),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(70),char(114), -char(105),char(99),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(76),char(111),char(119),char(101),char(114),char(76), -char(105),char(109),char(105),char(116),char(0),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(85),char(112),char(112),char(101),char(114),char(76),char(105),char(109), -char(105),char(116),char(0),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(77),char(97),char(120),char(70),char(111),char(114),char(99),char(101),char(0),char(109), -char(95),char(106),char(111),char(105),char(110),char(116),char(77),char(97),char(120),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(42),char(109), -char(95),char(108),char(105),char(110),char(107),char(78),char(97),char(109),char(101),char(0),char(42),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(78),char(97), -char(109),char(101),char(0),char(42),char(109),char(95),char(108),char(105),char(110),char(107),char(67),char(111),char(108),char(108),char(105),char(100),char(101),char(114),char(0),char(42), -char(109),char(95),char(112),char(97),char(100),char(100),char(105),char(110),char(103),char(80),char(116),char(114),char(0),char(109),char(95),char(98),char(97),char(115),char(101),char(87), -char(111),char(114),char(108),char(100),char(80),char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(98),char(97),char(115),char(101),char(87), -char(111),char(114),char(108),char(100),char(79),char(114),char(105),char(101),char(110),char(116),char(97),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(98),char(97), -char(115),char(101),char(76),char(105),char(110),char(101),char(97),char(114),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109),char(95),char(98), -char(97),char(115),char(101),char(65),char(110),char(103),char(117),char(108),char(97),char(114),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109), -char(95),char(98),char(97),char(115),char(101),char(73),char(110),char(101),char(114),char(116),char(105),char(97),char(0),char(109),char(95),char(98),char(97),char(115),char(101),char(77), -char(97),char(115),char(115),char(0),char(42),char(109),char(95),char(98),char(97),char(115),char(101),char(78),char(97),char(109),char(101),char(0),char(42),char(109),char(95),char(98), -char(97),char(115),char(101),char(67),char(111),char(108),char(108),char(105),char(100),char(101),char(114),char(0),char(109),char(95),char(99),char(111),char(108),char(79),char(98),char(106), -char(68),char(97),char(116),char(97),char(0),char(42),char(109),char(95),char(109),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(0),char(109),char(95), -char(108),char(105),char(110),char(107),char(0),char(0),char(0),char(0),char(84),char(89),char(80),char(69),char(99),char(0),char(0),char(0),char(99),char(104),char(97),char(114), -char(0),char(117),char(99),char(104),char(97),char(114),char(0),char(115),char(104),char(111),char(114),char(116),char(0),char(117),char(115),char(104),char(111),char(114),char(116),char(0), -char(105),char(110),char(116),char(0),char(108),char(111),char(110),char(103),char(0),char(117),char(108),char(111),char(110),char(103),char(0),char(102),char(108),char(111),char(97),char(116), -char(0),char(100),char(111),char(117),char(98),char(108),char(101),char(0),char(118),char(111),char(105),char(100),char(0),char(80),char(111),char(105),char(110),char(116),char(101),char(114), -char(65),char(114),char(114),char(97),char(121),char(0),char(98),char(116),char(80),char(104),char(121),char(115),char(105),char(99),char(115),char(83),char(121),char(115),char(116),char(101), -char(109),char(0),char(76),char(105),char(115),char(116),char(66),char(97),char(115),char(101),char(0),char(98),char(116),char(86),char(101),char(99),char(116),char(111),char(114),char(51), -char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(86),char(101),char(99),char(116),char(111),char(114),char(51),char(68), -char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(116),char(101),char(114),char(110),char(105), -char(111),char(110),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(116),char(101),char(114), -char(110),char(105),char(111),char(110),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(97),char(116), -char(114),char(105),char(120),char(51),char(120),char(51),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(97), -char(116),char(114),char(105),char(120),char(51),char(120),char(51),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116), -char(84),char(114),char(97),char(110),char(115),char(102),char(111),char(114),char(109),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98), -char(116),char(84),char(114),char(97),char(110),char(115),char(102),char(111),char(114),char(109),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97), -char(0),char(98),char(116),char(66),char(118),char(104),char(83),char(117),char(98),char(116),char(114),char(101),char(101),char(73),char(110),char(102),char(111),char(68),char(97),char(116), +char(109),char(75),char(101),char(121),char(115),char(0),char(109),char(95),char(103),char(105),char(109),char(112),char(97),char(99),char(116),char(83),char(117),char(98),char(84),char(121), +char(112),char(101),char(0),char(42),char(109),char(95),char(117),char(110),char(115),char(99),char(97),char(108),char(101),char(100),char(80),char(111),char(105),char(110),char(116),char(115), +char(70),char(108),char(111),char(97),char(116),char(80),char(116),char(114),char(0),char(42),char(109),char(95),char(117),char(110),char(115),char(99),char(97),char(108),char(101),char(100), +char(80),char(111),char(105),char(110),char(116),char(115),char(68),char(111),char(117),char(98),char(108),char(101),char(80),char(116),char(114),char(0),char(109),char(95),char(110),char(117), +char(109),char(85),char(110),char(115),char(99),char(97),char(108),char(101),char(100),char(80),char(111),char(105),char(110),char(116),char(115),char(0),char(109),char(95),char(112),char(97), +char(100),char(100),char(105),char(110),char(103),char(51),char(91),char(52),char(93),char(0),char(42),char(109),char(95),char(98),char(114),char(111),char(97),char(100),char(112),char(104), +char(97),char(115),char(101),char(72),char(97),char(110),char(100),char(108),char(101),char(0),char(42),char(109),char(95),char(99),char(111),char(108),char(108),char(105),char(115),char(105), +char(111),char(110),char(83),char(104),char(97),char(112),char(101),char(0),char(42),char(109),char(95),char(114),char(111),char(111),char(116),char(67),char(111),char(108),char(108),char(105), +char(115),char(105),char(111),char(110),char(83),char(104),char(97),char(112),char(101),char(0),char(109),char(95),char(119),char(111),char(114),char(108),char(100),char(84),char(114),char(97), +char(110),char(115),char(102),char(111),char(114),char(109),char(0),char(109),char(95),char(105),char(110),char(116),char(101),char(114),char(112),char(111),char(108),char(97),char(116),char(105), +char(111),char(110),char(87),char(111),char(114),char(108),char(100),char(84),char(114),char(97),char(110),char(115),char(102),char(111),char(114),char(109),char(0),char(109),char(95),char(105), +char(110),char(116),char(101),char(114),char(112),char(111),char(108),char(97),char(116),char(105),char(111),char(110),char(76),char(105),char(110),char(101),char(97),char(114),char(86),char(101), +char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109),char(95),char(105),char(110),char(116),char(101),char(114),char(112),char(111),char(108),char(97),char(116),char(105), +char(111),char(110),char(65),char(110),char(103),char(117),char(108),char(97),char(114),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109),char(95), +char(97),char(110),char(105),char(115),char(111),char(116),char(114),char(111),char(112),char(105),char(99),char(70),char(114),char(105),char(99),char(116),char(105),char(111),char(110),char(0), +char(109),char(95),char(99),char(111),char(110),char(116),char(97),char(99),char(116),char(80),char(114),char(111),char(99),char(101),char(115),char(115),char(105),char(110),char(103),char(84), +char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(0),char(109),char(95),char(100),char(101),char(97),char(99),char(116),char(105),char(118),char(97),char(116), +char(105),char(111),char(110),char(84),char(105),char(109),char(101),char(0),char(109),char(95),char(102),char(114),char(105),char(99),char(116),char(105),char(111),char(110),char(0),char(109), +char(95),char(114),char(111),char(108),char(108),char(105),char(110),char(103),char(70),char(114),char(105),char(99),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(99), +char(111),char(110),char(116),char(97),char(99),char(116),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(0),char(109),char(95),char(99),char(111),char(110),char(116), +char(97),char(99),char(116),char(83),char(116),char(105),char(102),char(102),char(110),char(101),char(115),char(115),char(0),char(109),char(95),char(114),char(101),char(115),char(116),char(105), +char(116),char(117),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(104),char(105),char(116),char(70),char(114),char(97),char(99),char(116),char(105),char(111),char(110), +char(0),char(109),char(95),char(99),char(99),char(100),char(83),char(119),char(101),char(112),char(116),char(83),char(112),char(104),char(101),char(114),char(101),char(82),char(97),char(100), +char(105),char(117),char(115),char(0),char(109),char(95),char(99),char(99),char(100),char(77),char(111),char(116),char(105),char(111),char(110),char(84),char(104),char(114),char(101),char(115), +char(104),char(111),char(108),char(100),char(0),char(109),char(95),char(104),char(97),char(115),char(65),char(110),char(105),char(115),char(111),char(116),char(114),char(111),char(112),char(105), +char(99),char(70),char(114),char(105),char(99),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(99),char(111),char(108),char(108),char(105),char(115),char(105),char(111), +char(110),char(70),char(108),char(97),char(103),char(115),char(0),char(109),char(95),char(105),char(115),char(108),char(97),char(110),char(100),char(84),char(97),char(103),char(49),char(0), +char(109),char(95),char(99),char(111),char(109),char(112),char(97),char(110),char(105),char(111),char(110),char(73),char(100),char(0),char(109),char(95),char(97),char(99),char(116),char(105), +char(118),char(97),char(116),char(105),char(111),char(110),char(83),char(116),char(97),char(116),char(101),char(49),char(0),char(109),char(95),char(105),char(110),char(116),char(101),char(114), +char(110),char(97),char(108),char(84),char(121),char(112),char(101),char(0),char(109),char(95),char(99),char(104),char(101),char(99),char(107),char(67),char(111),char(108),char(108),char(105), +char(100),char(101),char(87),char(105),char(116),char(104),char(0),char(109),char(95),char(116),char(97),char(117),char(0),char(109),char(95),char(100),char(97),char(109),char(112),char(105), +char(110),char(103),char(0),char(109),char(95),char(116),char(105),char(109),char(101),char(83),char(116),char(101),char(112),char(0),char(109),char(95),char(109),char(97),char(120),char(69), +char(114),char(114),char(111),char(114),char(82),char(101),char(100),char(117),char(99),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(115),char(111),char(114),char(0), +char(109),char(95),char(101),char(114),char(112),char(0),char(109),char(95),char(101),char(114),char(112),char(50),char(0),char(109),char(95),char(103),char(108),char(111),char(98),char(97), +char(108),char(67),char(102),char(109),char(0),char(109),char(95),char(115),char(112),char(108),char(105),char(116),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(80), +char(101),char(110),char(101),char(116),char(114),char(97),char(116),char(105),char(111),char(110),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(0), +char(109),char(95),char(115),char(112),char(108),char(105),char(116),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(84),char(117),char(114),char(110),char(69),char(114), +char(112),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(83),char(108),char(111),char(112),char(0),char(109),char(95),char(119),char(97),char(114), +char(109),char(115),char(116),char(97),char(114),char(116),char(105),char(110),char(103),char(70),char(97),char(99),char(116),char(111),char(114),char(0),char(109),char(95),char(109),char(97), +char(120),char(71),char(121),char(114),char(111),char(115),char(99),char(111),char(112),char(105),char(99),char(70),char(111),char(114),char(99),char(101),char(0),char(109),char(95),char(115), +char(105),char(110),char(103),char(108),char(101),char(65),char(120),char(105),char(115),char(82),char(111),char(108),char(108),char(105),char(110),char(103),char(70),char(114),char(105),char(99), +char(116),char(105),char(111),char(110),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(0),char(109),char(95),char(110),char(117),char(109),char(73), +char(116),char(101),char(114),char(97),char(116),char(105),char(111),char(110),char(115),char(0),char(109),char(95),char(115),char(111),char(108),char(118),char(101),char(114),char(77),char(111), +char(100),char(101),char(0),char(109),char(95),char(114),char(101),char(115),char(116),char(105),char(110),char(103),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(82), +char(101),char(115),char(116),char(105),char(116),char(117),char(116),char(105),char(111),char(110),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(0), +char(109),char(95),char(109),char(105),char(110),char(105),char(109),char(117),char(109),char(83),char(111),char(108),char(118),char(101),char(114),char(66),char(97),char(116),char(99),char(104), +char(83),char(105),char(122),char(101),char(0),char(109),char(95),char(115),char(112),char(108),char(105),char(116),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(0), +char(109),char(95),char(115),char(111),char(108),char(118),char(101),char(114),char(73),char(110),char(102),char(111),char(0),char(109),char(95),char(103),char(114),char(97),char(118),char(105), +char(116),char(121),char(0),char(109),char(95),char(99),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(79),char(98),char(106),char(101),char(99),char(116), +char(68),char(97),char(116),char(97),char(0),char(109),char(95),char(105),char(110),char(118),char(73),char(110),char(101),char(114),char(116),char(105),char(97),char(84),char(101),char(110), +char(115),char(111),char(114),char(87),char(111),char(114),char(108),char(100),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(86),char(101),char(108), +char(111),char(99),char(105),char(116),char(121),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(86),char(101),char(108),char(111),char(99), +char(105),char(116),char(121),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(70),char(97),char(99),char(116),char(111),char(114),char(0), +char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(70),char(97),char(99),char(116),char(111),char(114),char(0),char(109),char(95),char(103),char(114),char(97), +char(118),char(105),char(116),char(121),char(95),char(97),char(99),char(99),char(101),char(108),char(101),char(114),char(97),char(116),char(105),char(111),char(110),char(0),char(109),char(95), +char(105),char(110),char(118),char(73),char(110),char(101),char(114),char(116),char(105),char(97),char(76),char(111),char(99),char(97),char(108),char(0),char(109),char(95),char(116),char(111), +char(116),char(97),char(108),char(70),char(111),char(114),char(99),char(101),char(0),char(109),char(95),char(116),char(111),char(116),char(97),char(108),char(84),char(111),char(114),char(113), +char(117),char(101),char(0),char(109),char(95),char(105),char(110),char(118),char(101),char(114),char(115),char(101),char(77),char(97),char(115),char(115),char(0),char(109),char(95),char(108), +char(105),char(110),char(101),char(97),char(114),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108), +char(97),char(114),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(0),char(109),char(95),char(97),char(100),char(100),char(105),char(116),char(105),char(111),char(110), +char(97),char(108),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(70),char(97),char(99),char(116),char(111),char(114),char(0),char(109),char(95),char(97),char(100), +char(100),char(105),char(116),char(105),char(111),char(110),char(97),char(108),char(76),char(105),char(110),char(101),char(97),char(114),char(68),char(97),char(109),char(112),char(105),char(110), +char(103),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(83),char(113),char(114),char(0),char(109),char(95),char(97),char(100),char(100),char(105), +char(116),char(105),char(111),char(110),char(97),char(108),char(65),char(110),char(103),char(117),char(108),char(97),char(114),char(68),char(97),char(109),char(112),char(105),char(110),char(103), +char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(83),char(113),char(114),char(0),char(109),char(95),char(97),char(100),char(100),char(105),char(116), +char(105),char(111),char(110),char(97),char(108),char(65),char(110),char(103),char(117),char(108),char(97),char(114),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(70), +char(97),char(99),char(116),char(111),char(114),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(83),char(108),char(101),char(101),char(112),char(105), +char(110),char(103),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97), +char(114),char(83),char(108),char(101),char(101),char(112),char(105),char(110),char(103),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(0),char(109), +char(95),char(97),char(100),char(100),char(105),char(116),char(105),char(111),char(110),char(97),char(108),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(0),char(109), +char(95),char(110),char(117),char(109),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(82),char(111),char(119),char(115),char(0),char(110), +char(117),char(98),char(0),char(42),char(109),char(95),char(114),char(98),char(65),char(0),char(42),char(109),char(95),char(114),char(98),char(66),char(0),char(109),char(95),char(111), +char(98),char(106),char(101),char(99),char(116),char(84),char(121),char(112),char(101),char(0),char(109),char(95),char(117),char(115),char(101),char(114),char(67),char(111),char(110),char(115), +char(116),char(114),char(97),char(105),char(110),char(116),char(84),char(121),char(112),char(101),char(0),char(109),char(95),char(117),char(115),char(101),char(114),char(67),char(111),char(110), +char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(73),char(100),char(0),char(109),char(95),char(110),char(101),char(101),char(100),char(115),char(70),char(101),char(101), +char(100),char(98),char(97),char(99),char(107),char(0),char(109),char(95),char(97),char(112),char(112),char(108),char(105),char(101),char(100),char(73),char(109),char(112),char(117),char(108), +char(115),char(101),char(0),char(109),char(95),char(100),char(98),char(103),char(68),char(114),char(97),char(119),char(83),char(105),char(122),char(101),char(0),char(109),char(95),char(100), +char(105),char(115),char(97),char(98),char(108),char(101),char(67),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(115),char(66),char(101),char(116),char(119), +char(101),char(101),char(110),char(76),char(105),char(110),char(107),char(101),char(100),char(66),char(111),char(100),char(105),char(101),char(115),char(0),char(109),char(95),char(111),char(118), +char(101),char(114),char(114),char(105),char(100),char(101),char(78),char(117),char(109),char(83),char(111),char(108),char(118),char(101),char(114),char(73),char(116),char(101),char(114),char(97), +char(116),char(105),char(111),char(110),char(115),char(0),char(109),char(95),char(98),char(114),char(101),char(97),char(107),char(105),char(110),char(103),char(73),char(109),char(112),char(117), +char(108),char(115),char(101),char(84),char(104),char(114),char(101),char(115),char(104),char(111),char(108),char(100),char(0),char(109),char(95),char(105),char(115),char(69),char(110),char(97), +char(98),char(108),char(101),char(100),char(0),char(112),char(97),char(100),char(100),char(105),char(110),char(103),char(91),char(52),char(93),char(0),char(109),char(95),char(116),char(121), +char(112),char(101),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(109),char(95),char(112), +char(105),char(118),char(111),char(116),char(73),char(110),char(65),char(0),char(109),char(95),char(112),char(105),char(118),char(111),char(116),char(73),char(110),char(66),char(0),char(109), +char(95),char(114),char(98),char(65),char(70),char(114),char(97),char(109),char(101),char(0),char(109),char(95),char(114),char(98),char(66),char(70),char(114),char(97),char(109),char(101), +char(0),char(109),char(95),char(117),char(115),char(101),char(82),char(101),char(102),char(101),char(114),char(101),char(110),char(99),char(101),char(70),char(114),char(97),char(109),char(101), +char(65),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(79),char(110),char(108),char(121),char(0),char(109),char(95),char(101),char(110), +char(97),char(98),char(108),char(101),char(65),char(110),char(103),char(117),char(108),char(97),char(114),char(77),char(111),char(116),char(111),char(114),char(0),char(109),char(95),char(109), +char(111),char(116),char(111),char(114),char(84),char(97),char(114),char(103),char(101),char(116),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109), +char(95),char(109),char(97),char(120),char(77),char(111),char(116),char(111),char(114),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(0),char(109),char(95),char(108), +char(111),char(119),char(101),char(114),char(76),char(105),char(109),char(105),char(116),char(0),char(109),char(95),char(117),char(112),char(112),char(101),char(114),char(76),char(105),char(109), +char(105),char(116),char(0),char(109),char(95),char(108),char(105),char(109),char(105),char(116),char(83),char(111),char(102),char(116),char(110),char(101),char(115),char(115),char(0),char(109), +char(95),char(98),char(105),char(97),char(115),char(70),char(97),char(99),char(116),char(111),char(114),char(0),char(109),char(95),char(114),char(101),char(108),char(97),char(120),char(97), +char(116),char(105),char(111),char(110),char(70),char(97),char(99),char(116),char(111),char(114),char(0),char(109),char(95),char(112),char(97),char(100),char(100),char(105),char(110),char(103), +char(49),char(91),char(52),char(93),char(0),char(109),char(95),char(115),char(119),char(105),char(110),char(103),char(83),char(112),char(97),char(110),char(49),char(0),char(109),char(95), +char(115),char(119),char(105),char(110),char(103),char(83),char(112),char(97),char(110),char(50),char(0),char(109),char(95),char(116),char(119),char(105),char(115),char(116),char(83),char(112), +char(97),char(110),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(85),char(112),char(112),char(101),char(114),char(76),char(105),char(109),char(105), +char(116),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(76),char(111),char(119),char(101),char(114),char(76),char(105),char(109),char(105),char(116), +char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(85),char(112),char(112),char(101),char(114),char(76),char(105),char(109),char(105),char(116), +char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(76),char(111),char(119),char(101),char(114),char(76),char(105),char(109),char(105),char(116), +char(0),char(109),char(95),char(117),char(115),char(101),char(76),char(105),char(110),char(101),char(97),char(114),char(82),char(101),char(102),char(101),char(114),char(101),char(110),char(99), +char(101),char(70),char(114),char(97),char(109),char(101),char(65),char(0),char(109),char(95),char(117),char(115),char(101),char(79),char(102),char(102),char(115),char(101),char(116),char(70), +char(111),char(114),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(114),char(97),char(109),char(101),char(0),char(109),char(95), +char(54),char(100),char(111),char(102),char(68),char(97),char(116),char(97),char(0),char(109),char(95),char(115),char(112),char(114),char(105),char(110),char(103),char(69),char(110),char(97), +char(98),char(108),char(101),char(100),char(91),char(54),char(93),char(0),char(109),char(95),char(101),char(113),char(117),char(105),char(108),char(105),char(98),char(114),char(105),char(117), +char(109),char(80),char(111),char(105),char(110),char(116),char(91),char(54),char(93),char(0),char(109),char(95),char(115),char(112),char(114),char(105),char(110),char(103),char(83),char(116), +char(105),char(102),char(102),char(110),char(101),char(115),char(115),char(91),char(54),char(93),char(0),char(109),char(95),char(115),char(112),char(114),char(105),char(110),char(103),char(68), +char(97),char(109),char(112),char(105),char(110),char(103),char(91),char(54),char(93),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(66),char(111), +char(117),char(110),char(99),char(101),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(83),char(116),char(111),char(112),char(69),char(82),char(80), +char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(83),char(116),char(111),char(112),char(67),char(70),char(77),char(0),char(109),char(95),char(108), +char(105),char(110),char(101),char(97),char(114),char(77),char(111),char(116),char(111),char(114),char(69),char(82),char(80),char(0),char(109),char(95),char(108),char(105),char(110),char(101), +char(97),char(114),char(77),char(111),char(116),char(111),char(114),char(67),char(70),char(77),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(84), +char(97),char(114),char(103),char(101),char(116),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109),char(95),char(108),char(105),char(110),char(101), +char(97),char(114),char(77),char(97),char(120),char(77),char(111),char(116),char(111),char(114),char(70),char(111),char(114),char(99),char(101),char(0),char(109),char(95),char(108),char(105), +char(110),char(101),char(97),char(114),char(83),char(101),char(114),char(118),char(111),char(84),char(97),char(114),char(103),char(101),char(116),char(0),char(109),char(95),char(108),char(105), +char(110),char(101),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(83),char(116),char(105),char(102),char(102),char(110),char(101),char(115),char(115),char(0), +char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(68),char(97),char(109),char(112),char(105),char(110), +char(103),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(69),char(113),char(117),char(105),char(108),char(105),char(98),char(114),char(105),char(117), +char(109),char(80),char(111),char(105),char(110),char(116),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(69),char(110),char(97),char(98),char(108), +char(101),char(77),char(111),char(116),char(111),char(114),char(91),char(52),char(93),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(83),char(101), +char(114),char(118),char(111),char(77),char(111),char(116),char(111),char(114),char(91),char(52),char(93),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114), +char(69),char(110),char(97),char(98),char(108),char(101),char(83),char(112),char(114),char(105),char(110),char(103),char(91),char(52),char(93),char(0),char(109),char(95),char(108),char(105), +char(110),char(101),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(83),char(116),char(105),char(102),char(102),char(110),char(101),char(115),char(115),char(76), +char(105),char(109),char(105),char(116),char(101),char(100),char(91),char(52),char(93),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114),char(83),char(112), +char(114),char(105),char(110),char(103),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(76),char(105),char(109),char(105),char(116),char(101),char(100),char(91),char(52), +char(93),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(66),char(111),char(117),char(110),char(99),char(101),char(0),char(109),char(95), +char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(83),char(116),char(111),char(112),char(69),char(82),char(80),char(0),char(109),char(95),char(97),char(110),char(103), +char(117),char(108),char(97),char(114),char(83),char(116),char(111),char(112),char(67),char(70),char(77),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97), +char(114),char(77),char(111),char(116),char(111),char(114),char(69),char(82),char(80),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(77), +char(111),char(116),char(111),char(114),char(67),char(70),char(77),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(84),char(97),char(114), +char(103),char(101),char(116),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97), +char(114),char(77),char(97),char(120),char(77),char(111),char(116),char(111),char(114),char(70),char(111),char(114),char(99),char(101),char(0),char(109),char(95),char(97),char(110),char(103), +char(117),char(108),char(97),char(114),char(83),char(101),char(114),char(118),char(111),char(84),char(97),char(114),char(103),char(101),char(116),char(0),char(109),char(95),char(97),char(110), +char(103),char(117),char(108),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(83),char(116),char(105),char(102),char(102),char(110),char(101),char(115),char(115), +char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(68),char(97),char(109),char(112), +char(105),char(110),char(103),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(69),char(113),char(117),char(105),char(108),char(105),char(98), +char(114),char(105),char(117),char(109),char(80),char(111),char(105),char(110),char(116),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(69), +char(110),char(97),char(98),char(108),char(101),char(77),char(111),char(116),char(111),char(114),char(91),char(52),char(93),char(0),char(109),char(95),char(97),char(110),char(103),char(117), +char(108),char(97),char(114),char(83),char(101),char(114),char(118),char(111),char(77),char(111),char(116),char(111),char(114),char(91),char(52),char(93),char(0),char(109),char(95),char(97), +char(110),char(103),char(117),char(108),char(97),char(114),char(69),char(110),char(97),char(98),char(108),char(101),char(83),char(112),char(114),char(105),char(110),char(103),char(91),char(52), +char(93),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(83),char(116),char(105), +char(102),char(102),char(110),char(101),char(115),char(115),char(76),char(105),char(109),char(105),char(116),char(101),char(100),char(91),char(52),char(93),char(0),char(109),char(95),char(97), +char(110),char(103),char(117),char(108),char(97),char(114),char(83),char(112),char(114),char(105),char(110),char(103),char(68),char(97),char(109),char(112),char(105),char(110),char(103),char(76), +char(105),char(109),char(105),char(116),char(101),char(100),char(91),char(52),char(93),char(0),char(109),char(95),char(114),char(111),char(116),char(97),char(116),char(101),char(79),char(114), +char(100),char(101),char(114),char(0),char(109),char(95),char(97),char(120),char(105),char(115),char(73),char(110),char(65),char(0),char(109),char(95),char(97),char(120),char(105),char(115), +char(73),char(110),char(66),char(0),char(109),char(95),char(114),char(97),char(116),char(105),char(111),char(0),char(109),char(95),char(108),char(105),char(110),char(101),char(97),char(114), +char(83),char(116),char(105),char(102),char(102),char(110),char(101),char(115),char(115),char(0),char(109),char(95),char(97),char(110),char(103),char(117),char(108),char(97),char(114),char(83), +char(116),char(105),char(102),char(102),char(110),char(101),char(115),char(115),char(0),char(109),char(95),char(118),char(111),char(108),char(117),char(109),char(101),char(83),char(116),char(105), +char(102),char(102),char(110),char(101),char(115),char(115),char(0),char(42),char(109),char(95),char(109),char(97),char(116),char(101),char(114),char(105),char(97),char(108),char(0),char(109), +char(95),char(112),char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(112),char(114),char(101),char(118),char(105),char(111),char(117),char(115), +char(80),char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(0),char(109),char(95),char(118),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0), +char(109),char(95),char(97),char(99),char(99),char(117),char(109),char(117),char(108),char(97),char(116),char(101),char(100),char(70),char(111),char(114),char(99),char(101),char(0),char(109), +char(95),char(110),char(111),char(114),char(109),char(97),char(108),char(0),char(109),char(95),char(97),char(114),char(101),char(97),char(0),char(109),char(95),char(97),char(116),char(116), +char(97),char(99),char(104),char(0),char(109),char(95),char(110),char(111),char(100),char(101),char(73),char(110),char(100),char(105),char(99),char(101),char(115),char(91),char(50),char(93), +char(0),char(109),char(95),char(114),char(101),char(115),char(116),char(76),char(101),char(110),char(103),char(116),char(104),char(0),char(109),char(95),char(98),char(98),char(101),char(110), +char(100),char(105),char(110),char(103),char(0),char(109),char(95),char(110),char(111),char(100),char(101),char(73),char(110),char(100),char(105),char(99),char(101),char(115),char(91),char(51), +char(93),char(0),char(109),char(95),char(114),char(101),char(115),char(116),char(65),char(114),char(101),char(97),char(0),char(109),char(95),char(99),char(48),char(91),char(52),char(93), +char(0),char(109),char(95),char(110),char(111),char(100),char(101),char(73),char(110),char(100),char(105),char(99),char(101),char(115),char(91),char(52),char(93),char(0),char(109),char(95), +char(114),char(101),char(115),char(116),char(86),char(111),char(108),char(117),char(109),char(101),char(0),char(109),char(95),char(99),char(49),char(0),char(109),char(95),char(99),char(50), +char(0),char(109),char(95),char(99),char(48),char(0),char(109),char(95),char(108),char(111),char(99),char(97),char(108),char(70),char(114),char(97),char(109),char(101),char(0),char(42), +char(109),char(95),char(114),char(105),char(103),char(105),char(100),char(66),char(111),char(100),char(121),char(0),char(109),char(95),char(110),char(111),char(100),char(101),char(73),char(110), +char(100),char(101),char(120),char(0),char(109),char(95),char(97),char(101),char(114),char(111),char(77),char(111),char(100),char(101),char(108),char(0),char(109),char(95),char(98),char(97), +char(117),char(109),char(103),char(97),char(114),char(116),char(101),char(0),char(109),char(95),char(100),char(114),char(97),char(103),char(0),char(109),char(95),char(108),char(105),char(102), +char(116),char(0),char(109),char(95),char(112),char(114),char(101),char(115),char(115),char(117),char(114),char(101),char(0),char(109),char(95),char(118),char(111),char(108),char(117),char(109), +char(101),char(0),char(109),char(95),char(100),char(121),char(110),char(97),char(109),char(105),char(99),char(70),char(114),char(105),char(99),char(116),char(105),char(111),char(110),char(0), +char(109),char(95),char(112),char(111),char(115),char(101),char(77),char(97),char(116),char(99),char(104),char(0),char(109),char(95),char(114),char(105),char(103),char(105),char(100),char(67), +char(111),char(110),char(116),char(97),char(99),char(116),char(72),char(97),char(114),char(100),char(110),char(101),char(115),char(115),char(0),char(109),char(95),char(107),char(105),char(110), +char(101),char(116),char(105),char(99),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(72),char(97),char(114),char(100),char(110),char(101),char(115),char(115),char(0), +char(109),char(95),char(115),char(111),char(102),char(116),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(72),char(97),char(114),char(100),char(110),char(101),char(115), +char(115),char(0),char(109),char(95),char(97),char(110),char(99),char(104),char(111),char(114),char(72),char(97),char(114),char(100),char(110),char(101),char(115),char(115),char(0),char(109), +char(95),char(115),char(111),char(102),char(116),char(82),char(105),char(103),char(105),char(100),char(67),char(108),char(117),char(115),char(116),char(101),char(114),char(72),char(97),char(114), +char(100),char(110),char(101),char(115),char(115),char(0),char(109),char(95),char(115),char(111),char(102),char(116),char(75),char(105),char(110),char(101),char(116),char(105),char(99),char(67), +char(108),char(117),char(115),char(116),char(101),char(114),char(72),char(97),char(114),char(100),char(110),char(101),char(115),char(115),char(0),char(109),char(95),char(115),char(111),char(102), +char(116),char(83),char(111),char(102),char(116),char(67),char(108),char(117),char(115),char(116),char(101),char(114),char(72),char(97),char(114),char(100),char(110),char(101),char(115),char(115), +char(0),char(109),char(95),char(115),char(111),char(102),char(116),char(82),char(105),char(103),char(105),char(100),char(67),char(108),char(117),char(115),char(116),char(101),char(114),char(73), +char(109),char(112),char(117),char(108),char(115),char(101),char(83),char(112),char(108),char(105),char(116),char(0),char(109),char(95),char(115),char(111),char(102),char(116),char(75),char(105), +char(110),char(101),char(116),char(105),char(99),char(67),char(108),char(117),char(115),char(116),char(101),char(114),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(83), +char(112),char(108),char(105),char(116),char(0),char(109),char(95),char(115),char(111),char(102),char(116),char(83),char(111),char(102),char(116),char(67),char(108),char(117),char(115),char(116), +char(101),char(114),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(83),char(112),char(108),char(105),char(116),char(0),char(109),char(95),char(109),char(97),char(120), +char(86),char(111),char(108),char(117),char(109),char(101),char(0),char(109),char(95),char(116),char(105),char(109),char(101),char(83),char(99),char(97),char(108),char(101),char(0),char(109), +char(95),char(118),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(73),char(116),char(101),char(114),char(97),char(116),char(105),char(111),char(110),char(115),char(0), +char(109),char(95),char(112),char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(73),char(116),char(101),char(114),char(97),char(116),char(105),char(111),char(110),char(115), +char(0),char(109),char(95),char(100),char(114),char(105),char(102),char(116),char(73),char(116),char(101),char(114),char(97),char(116),char(105),char(111),char(110),char(115),char(0),char(109), +char(95),char(99),char(108),char(117),char(115),char(116),char(101),char(114),char(73),char(116),char(101),char(114),char(97),char(116),char(105),char(111),char(110),char(115),char(0),char(109), +char(95),char(114),char(111),char(116),char(0),char(109),char(95),char(115),char(99),char(97),char(108),char(101),char(0),char(109),char(95),char(97),char(113),char(113),char(0),char(109), +char(95),char(99),char(111),char(109),char(0),char(42),char(109),char(95),char(112),char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(115),char(0),char(42),char(109), +char(95),char(119),char(101),char(105),char(103),char(104),char(116),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(80),char(111),char(115),char(105),char(116),char(105), +char(111),char(110),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(87),char(101),char(105),char(103),char(116),char(115),char(0),char(109),char(95),char(98),char(118), +char(111),char(108),char(117),char(109),char(101),char(0),char(109),char(95),char(98),char(102),char(114),char(97),char(109),char(101),char(0),char(109),char(95),char(102),char(114),char(97), +char(109),char(101),char(120),char(102),char(111),char(114),char(109),char(0),char(109),char(95),char(108),char(111),char(99),char(105),char(105),char(0),char(109),char(95),char(105),char(110), +char(118),char(119),char(105),char(0),char(109),char(95),char(118),char(105),char(109),char(112),char(117),char(108),char(115),char(101),char(115),char(91),char(50),char(93),char(0),char(109), +char(95),char(100),char(105),char(109),char(112),char(117),char(108),char(115),char(101),char(115),char(91),char(50),char(93),char(0),char(109),char(95),char(108),char(118),char(0),char(109), +char(95),char(97),char(118),char(0),char(42),char(109),char(95),char(102),char(114),char(97),char(109),char(101),char(114),char(101),char(102),char(115),char(0),char(42),char(109),char(95), +char(110),char(111),char(100),char(101),char(73),char(110),char(100),char(105),char(99),char(101),char(115),char(0),char(42),char(109),char(95),char(109),char(97),char(115),char(115),char(101), +char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(70),char(114),char(97),char(109),char(101),char(82),char(101),char(102),char(115),char(0),char(109),char(95),char(110), +char(117),char(109),char(78),char(111),char(100),char(101),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(77),char(97),char(115),char(115),char(101),char(115),char(0), +char(109),char(95),char(105),char(100),char(109),char(97),char(115),char(115),char(0),char(109),char(95),char(105),char(109),char(97),char(115),char(115),char(0),char(109),char(95),char(110), +char(118),char(105),char(109),char(112),char(117),char(108),char(115),char(101),char(115),char(0),char(109),char(95),char(110),char(100),char(105),char(109),char(112),char(117),char(108),char(115), +char(101),char(115),char(0),char(109),char(95),char(110),char(100),char(97),char(109),char(112),char(105),char(110),char(103),char(0),char(109),char(95),char(108),char(100),char(97),char(109), +char(112),char(105),char(110),char(103),char(0),char(109),char(95),char(97),char(100),char(97),char(109),char(112),char(105),char(110),char(103),char(0),char(109),char(95),char(109),char(97), +char(116),char(99),char(104),char(105),char(110),char(103),char(0),char(109),char(95),char(109),char(97),char(120),char(83),char(101),char(108),char(102),char(67),char(111),char(108),char(108), +char(105),char(115),char(105),char(111),char(110),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(0),char(109),char(95),char(115),char(101),char(108),char(102),char(67), +char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(73),char(109),char(112),char(117),char(108),char(115),char(101),char(70),char(97),char(99),char(116),char(111), +char(114),char(0),char(109),char(95),char(99),char(111),char(110),char(116),char(97),char(105),char(110),char(115),char(65),char(110),char(99),char(104),char(111),char(114),char(0),char(109), +char(95),char(99),char(111),char(108),char(108),char(105),char(100),char(101),char(0),char(109),char(95),char(99),char(108),char(117),char(115),char(116),char(101),char(114),char(73),char(110), +char(100),char(101),char(120),char(0),char(42),char(109),char(95),char(98),char(111),char(100),char(121),char(65),char(0),char(42),char(109),char(95),char(98),char(111),char(100),char(121), +char(66),char(0),char(109),char(95),char(114),char(101),char(102),char(115),char(91),char(50),char(93),char(0),char(109),char(95),char(99),char(102),char(109),char(0),char(109),char(95), +char(115),char(112),char(108),char(105),char(116),char(0),char(109),char(95),char(100),char(101),char(108),char(101),char(116),char(101),char(0),char(109),char(95),char(114),char(101),char(108), +char(80),char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(91),char(50),char(93),char(0),char(109),char(95),char(98),char(111),char(100),char(121),char(65),char(116), +char(121),char(112),char(101),char(0),char(109),char(95),char(98),char(111),char(100),char(121),char(66),char(116),char(121),char(112),char(101),char(0),char(109),char(95),char(106),char(111), +char(105),char(110),char(116),char(84),char(121),char(112),char(101),char(0),char(42),char(109),char(95),char(112),char(111),char(115),char(101),char(0),char(42),char(42),char(109),char(95), +char(109),char(97),char(116),char(101),char(114),char(105),char(97),char(108),char(115),char(0),char(42),char(109),char(95),char(110),char(111),char(100),char(101),char(115),char(0),char(42), +char(109),char(95),char(108),char(105),char(110),char(107),char(115),char(0),char(42),char(109),char(95),char(102),char(97),char(99),char(101),char(115),char(0),char(42),char(109),char(95), +char(116),char(101),char(116),char(114),char(97),char(104),char(101),char(100),char(114),char(97),char(0),char(42),char(109),char(95),char(97),char(110),char(99),char(104),char(111),char(114), +char(115),char(0),char(42),char(109),char(95),char(99),char(108),char(117),char(115),char(116),char(101),char(114),char(115),char(0),char(42),char(109),char(95),char(106),char(111),char(105), +char(110),char(116),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(77),char(97),char(116),char(101),char(114),char(105),char(97),char(108),char(115),char(0),char(109), +char(95),char(110),char(117),char(109),char(76),char(105),char(110),char(107),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(70),char(97),char(99),char(101),char(115), +char(0),char(109),char(95),char(110),char(117),char(109),char(84),char(101),char(116),char(114),char(97),char(104),char(101),char(100),char(114),char(97),char(0),char(109),char(95),char(110), +char(117),char(109),char(65),char(110),char(99),char(104),char(111),char(114),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(67),char(108),char(117),char(115),char(116), +char(101),char(114),char(115),char(0),char(109),char(95),char(110),char(117),char(109),char(74),char(111),char(105),char(110),char(116),char(115),char(0),char(109),char(95),char(99),char(111), +char(110),char(102),char(105),char(103),char(0),char(109),char(95),char(122),char(101),char(114),char(111),char(82),char(111),char(116),char(80),char(97),char(114),char(101),char(110),char(116), +char(84),char(111),char(84),char(104),char(105),char(115),char(0),char(109),char(95),char(112),char(97),char(114),char(101),char(110),char(116),char(67),char(111),char(109),char(84),char(111), +char(84),char(104),char(105),char(115),char(67),char(111),char(109),char(79),char(102),char(102),char(115),char(101),char(116),char(0),char(109),char(95),char(116),char(104),char(105),char(115), +char(80),char(105),char(118),char(111),char(116),char(84),char(111),char(84),char(104),char(105),char(115),char(67),char(111),char(109),char(79),char(102),char(102),char(115),char(101),char(116), +char(0),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(65),char(120),char(105),char(115),char(84),char(111),char(112),char(91),char(54),char(93),char(0),char(109), +char(95),char(106),char(111),char(105),char(110),char(116),char(65),char(120),char(105),char(115),char(66),char(111),char(116),char(116),char(111),char(109),char(91),char(54),char(93),char(0), +char(109),char(95),char(108),char(105),char(110),char(107),char(73),char(110),char(101),char(114),char(116),char(105),char(97),char(0),char(109),char(95),char(108),char(105),char(110),char(107), +char(77),char(97),char(115),char(115),char(0),char(109),char(95),char(112),char(97),char(114),char(101),char(110),char(116),char(73),char(110),char(100),char(101),char(120),char(0),char(109), +char(95),char(100),char(111),char(102),char(67),char(111),char(117),char(110),char(116),char(0),char(109),char(95),char(112),char(111),char(115),char(86),char(97),char(114),char(67),char(111), +char(117),char(110),char(116),char(0),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(80),char(111),char(115),char(91),char(55),char(93),char(0),char(109),char(95), +char(106),char(111),char(105),char(110),char(116),char(86),char(101),char(108),char(91),char(54),char(93),char(0),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(84), +char(111),char(114),char(113),char(117),char(101),char(91),char(54),char(93),char(0),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(68),char(97),char(109),char(112), +char(105),char(110),char(103),char(0),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(70),char(114),char(105),char(99),char(116),char(105),char(111),char(110),char(0), +char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(76),char(111),char(119),char(101),char(114),char(76),char(105),char(109),char(105),char(116),char(0),char(109),char(95), +char(106),char(111),char(105),char(110),char(116),char(85),char(112),char(112),char(101),char(114),char(76),char(105),char(109),char(105),char(116),char(0),char(109),char(95),char(106),char(111), +char(105),char(110),char(116),char(77),char(97),char(120),char(70),char(111),char(114),char(99),char(101),char(0),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(77), +char(97),char(120),char(86),char(101),char(108),char(111),char(99),char(105),char(116),char(121),char(0),char(42),char(109),char(95),char(108),char(105),char(110),char(107),char(78),char(97), +char(109),char(101),char(0),char(42),char(109),char(95),char(106),char(111),char(105),char(110),char(116),char(78),char(97),char(109),char(101),char(0),char(42),char(109),char(95),char(108), +char(105),char(110),char(107),char(67),char(111),char(108),char(108),char(105),char(100),char(101),char(114),char(0),char(42),char(109),char(95),char(112),char(97),char(100),char(100),char(105), +char(110),char(103),char(80),char(116),char(114),char(0),char(109),char(95),char(98),char(97),char(115),char(101),char(87),char(111),char(114),char(108),char(100),char(84),char(114),char(97), +char(110),char(115),char(102),char(111),char(114),char(109),char(0),char(109),char(95),char(98),char(97),char(115),char(101),char(73),char(110),char(101),char(114),char(116),char(105),char(97), +char(0),char(109),char(95),char(98),char(97),char(115),char(101),char(77),char(97),char(115),char(115),char(0),char(42),char(109),char(95),char(98),char(97),char(115),char(101),char(78), +char(97),char(109),char(101),char(0),char(42),char(109),char(95),char(98),char(97),char(115),char(101),char(67),char(111),char(108),char(108),char(105),char(100),char(101),char(114),char(0), +char(84),char(89),char(80),char(69),char(95),char(0),char(0),char(0),char(99),char(104),char(97),char(114),char(0),char(117),char(99),char(104),char(97),char(114),char(0),char(115), +char(104),char(111),char(114),char(116),char(0),char(117),char(115),char(104),char(111),char(114),char(116),char(0),char(105),char(110),char(116),char(0),char(108),char(111),char(110),char(103), +char(0),char(117),char(108),char(111),char(110),char(103),char(0),char(102),char(108),char(111),char(97),char(116),char(0),char(100),char(111),char(117),char(98),char(108),char(101),char(0), +char(118),char(111),char(105),char(100),char(0),char(80),char(111),char(105),char(110),char(116),char(101),char(114),char(65),char(114),char(114),char(97),char(121),char(0),char(98),char(116), +char(80),char(104),char(121),char(115),char(105),char(99),char(115),char(83),char(121),char(115),char(116),char(101),char(109),char(0),char(76),char(105),char(115),char(116),char(66),char(97), +char(115),char(101),char(0),char(98),char(116),char(86),char(101),char(99),char(116),char(111),char(114),char(51),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116), +char(97),char(0),char(98),char(116),char(86),char(101),char(99),char(116),char(111),char(114),char(51),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116), +char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(116),char(101),char(114),char(110),char(105),char(111),char(110),char(70),char(108),char(111),char(97),char(116),char(68), +char(97),char(116),char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(116),char(101),char(114),char(110),char(105),char(111),char(110),char(68),char(111),char(117),char(98), +char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(97),char(116),char(114),char(105),char(120),char(51),char(120),char(51),char(70),char(108), +char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(97),char(116),char(114),char(105),char(120),char(51),char(120),char(51),char(68), +char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114),char(97),char(110),char(115),char(102),char(111),char(114), +char(109),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114),char(97),char(110),char(115),char(102),char(111), +char(114),char(109),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(66),char(118),char(104),char(83),char(117), +char(98),char(116),char(114),char(101),char(101),char(73),char(110),char(102),char(111),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(79),char(112),char(116),char(105), +char(109),char(105),char(122),char(101),char(100),char(66),char(118),char(104),char(78),char(111),char(100),char(101),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116), char(97),char(0),char(98),char(116),char(79),char(112),char(116),char(105),char(109),char(105),char(122),char(101),char(100),char(66),char(118),char(104),char(78),char(111),char(100),char(101), -char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(79),char(112),char(116),char(105),char(109),char(105),char(122),char(101), -char(100),char(66),char(118),char(104),char(78),char(111),char(100),char(101),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98), -char(116),char(81),char(117),char(97),char(110),char(116),char(105),char(122),char(101),char(100),char(66),char(118),char(104),char(78),char(111),char(100),char(101),char(68),char(97),char(116), -char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(110),char(116),char(105),char(122),char(101),char(100),char(66),char(118),char(104),char(70),char(108),char(111),char(97), -char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(110),char(116),char(105),char(122),char(101),char(100),char(66),char(118),char(104), -char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(108),char(108),char(105),char(115),char(105), -char(111),char(110),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(116),char(97),char(116),char(105),char(99), -char(80),char(108),char(97),char(110),char(101),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110), -char(118),char(101),char(120),char(73),char(110),char(116),char(101),char(114),char(110),char(97),char(108),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97), -char(0),char(98),char(116),char(80),char(111),char(115),char(105),char(116),char(105),char(111),char(110),char(65),char(110),char(100),char(82),char(97),char(100),char(105),char(117),char(115), -char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),char(83),char(112),char(104),char(101),char(114),char(101),char(83),char(104),char(97),char(112),char(101),char(68), -char(97),char(116),char(97),char(0),char(98),char(116),char(73),char(110),char(116),char(73),char(110),char(100),char(101),char(120),char(68),char(97),char(116),char(97),char(0),char(98), -char(116),char(83),char(104),char(111),char(114),char(116),char(73),char(110),char(116),char(73),char(110),char(100),char(101),char(120),char(68),char(97),char(116),char(97),char(0),char(98), -char(116),char(83),char(104),char(111),char(114),char(116),char(73),char(110),char(116),char(73),char(110),char(100),char(101),char(120),char(84),char(114),char(105),char(112),char(108),char(101), -char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(104),char(97),char(114),char(73),char(110),char(100),char(101),char(120),char(84),char(114),char(105), -char(112),char(108),char(101),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(101),char(115),char(104),char(80),char(97),char(114),char(116),char(68), -char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(116),char(114),char(105),char(100),char(105),char(110),char(103),char(77),char(101),char(115),char(104),char(73),char(110), -char(116),char(101),char(114),char(102),char(97),char(99),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114),char(105),char(97),char(110),char(103), -char(108),char(101),char(77),char(101),char(115),char(104),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114), -char(105),char(97),char(110),char(103),char(108),char(101),char(73),char(110),char(102),char(111),char(77),char(97),char(112),char(68),char(97),char(116),char(97),char(0),char(98),char(116), -char(83),char(99),char(97),char(108),char(101),char(100),char(84),char(114),char(105),char(97),char(110),char(103),char(108),char(101),char(77),char(101),char(115),char(104),char(83),char(104), -char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(109),char(112),char(111),char(117),char(110),char(100),char(83),char(104), -char(97),char(112),char(101),char(67),char(104),char(105),char(108),char(100),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(109),char(112),char(111), -char(117),char(110),char(100),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(121),char(108),char(105),char(110), -char(100),char(101),char(114),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(101),char(83), -char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(97),char(112),char(115),char(117),char(108),char(101),char(83),char(104), +char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(110),char(116),char(105),char(122), +char(101),char(100),char(66),char(118),char(104),char(78),char(111),char(100),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(81),char(117),char(97),char(110), +char(116),char(105),char(122),char(101),char(100),char(66),char(118),char(104),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116), +char(81),char(117),char(97),char(110),char(116),char(105),char(122),char(101),char(100),char(66),char(118),char(104),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97), +char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(83),char(104),char(97),char(112),char(101),char(68), +char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(116),char(97),char(116),char(105),char(99),char(80),char(108),char(97),char(110),char(101),char(83),char(104),char(97), +char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(118),char(101),char(120),char(73),char(110),char(116),char(101),char(114), +char(110),char(97),char(108),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(80),char(111),char(115),char(105),char(116), +char(105),char(111),char(110),char(65),char(110),char(100),char(82),char(97),char(100),char(105),char(117),char(115),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105), +char(83),char(112),char(104),char(101),char(114),char(101),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(73),char(110), +char(116),char(73),char(110),char(100),char(101),char(120),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(104),char(111),char(114),char(116),char(73),char(110), +char(116),char(73),char(110),char(100),char(101),char(120),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(104),char(111),char(114),char(116),char(73),char(110), +char(116),char(73),char(110),char(100),char(101),char(120),char(84),char(114),char(105),char(112),char(108),char(101),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116), +char(67),char(104),char(97),char(114),char(73),char(110),char(100),char(101),char(120),char(84),char(114),char(105),char(112),char(108),char(101),char(116),char(68),char(97),char(116),char(97), +char(0),char(98),char(116),char(77),char(101),char(115),char(104),char(80),char(97),char(114),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(116), +char(114),char(105),char(100),char(105),char(110),char(103),char(77),char(101),char(115),char(104),char(73),char(110),char(116),char(101),char(114),char(102),char(97),char(99),char(101),char(68), +char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114),char(105),char(97),char(110),char(103),char(108),char(101),char(77),char(101),char(115),char(104),char(83),char(104), char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(114),char(105),char(97),char(110),char(103),char(108),char(101),char(73),char(110), -char(102),char(111),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(80),char(101),char(114),char(115),char(105),char(115),char(116),char(101),char(110),char(116),char(77), -char(97),char(110),char(105),char(102),char(111),char(108),char(100),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116), -char(67),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(79),char(98),char(106),char(101),char(99),char(116),char(68),char(111),char(117),char(98),char(108), -char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(80),char(101),char(114),char(115),char(105),char(115),char(116),char(101),char(110),char(116),char(77),char(97), -char(110),char(105),char(102),char(111),char(108),char(100),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111), -char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(79),char(98),char(106),char(101),char(99),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97), -char(116),char(97),char(0),char(98),char(116),char(71),char(73),char(109),char(112),char(97),char(99),char(116),char(77),char(101),char(115),char(104),char(83),char(104),char(97),char(112), -char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(118),char(101),char(120),char(72),char(117),char(108),char(108),char(83),char(104), -char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(83),char(111),char(108), -char(118),char(101),char(114),char(73),char(110),char(102),char(111),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116), -char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(83),char(111),char(108),char(118),char(101),char(114),char(73),char(110),char(102),char(111),char(70),char(108),char(111), -char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(68),char(121),char(110),char(97),char(109),char(105),char(99),char(115),char(87),char(111),char(114), -char(108),char(100),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(68),char(121),char(110),char(97),char(109), -char(105),char(99),char(115),char(87),char(111),char(114),char(108),char(100),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116), -char(82),char(105),char(103),char(105),char(100),char(66),char(111),char(100),char(121),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98), -char(116),char(82),char(105),char(103),char(105),char(100),char(66),char(111),char(100),char(121),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97), -char(0),char(98),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(73),char(110),char(102),char(111),char(49),char(0),char(98), -char(116),char(84),char(121),char(112),char(101),char(100),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(108),char(111),char(97), -char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(121),char(112),char(101),char(100),char(67),char(111),char(110),char(115),char(116),char(114),char(97), -char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(82),char(105),char(103),char(105),char(100),char(66),char(111),char(100),char(121),char(68), -char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(121),char(112),char(101),char(100),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110), -char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(80),char(111),char(105),char(110),char(116),char(50), -char(80),char(111),char(105),char(110),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(108),char(111),char(97),char(116), -char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(80),char(111),char(105),char(110),char(116),char(50),char(80),char(111),char(105),char(110),char(116),char(67),char(111), -char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(50),char(0), -char(98),char(116),char(80),char(111),char(105),char(110),char(116),char(50),char(80),char(111),char(105),char(110),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97), -char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(72),char(105),char(110),char(103), -char(101),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116), -char(97),char(0),char(98),char(116),char(72),char(105),char(110),char(103),char(101),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(70), -char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(72),char(105),char(110),char(103),char(101),char(67),char(111),char(110),char(115), -char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(50),char(0),char(98),char(116), -char(67),char(111),char(110),char(101),char(84),char(119),char(105),char(115),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68), -char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(101),char(84),char(119),char(105),char(115), -char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101), -char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68), -char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(67),char(111),char(110), -char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(50),char(0),char(98), -char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(83),char(112),char(114),char(105),char(110),char(103),char(67),char(111), -char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114), -char(105),char(99),char(54),char(68),char(111),char(102),char(83),char(112),char(114),char(105),char(110),char(103),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105), -char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(50),char(0),char(98),char(116),char(71),char(101),char(110),char(101), -char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(83),char(112),char(114),char(105),char(110),char(103),char(50),char(67),char(111),char(110),char(115),char(116),char(114), -char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68), -char(111),char(102),char(83),char(112),char(114),char(105),char(110),char(103),char(50),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68), -char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(50),char(0),char(98),char(116),char(83),char(108),char(105),char(100),char(101),char(114),char(67), -char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(108),char(105),char(100), -char(101),char(114),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97), -char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(97),char(114),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(70), -char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(97),char(114),char(67),char(111),char(110),char(115),char(116), -char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116), -char(66),char(111),char(100),char(121),char(77),char(97),char(116),char(101),char(114),char(105),char(97),char(108),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102), -char(116),char(66),char(111),char(100),char(121),char(78),char(111),char(100),char(101),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111), -char(100),char(121),char(76),char(105),char(110),char(107),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(70), -char(97),char(99),char(101),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(84),char(101),char(116),char(114), -char(97),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(82),char(105),char(103),char(105),char(100),char(65),char(110),char(99),char(104),char(111), -char(114),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(67),char(111),char(110),char(102),char(105),char(103), -char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(80),char(111),char(115),char(101),char(68),char(97),char(116), -char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(67),char(108),char(117),char(115),char(116),char(101),char(114),char(68),char(97),char(116), -char(97),char(0),char(98),char(116),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(74),char(111),char(105),char(110),char(116),char(68),char(97),char(116), -char(97),char(0),char(98),char(116),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116), -char(97),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(76),char(105),char(110),char(107),char(68),char(111),char(117), -char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(76), -char(105),char(110),char(107),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105), -char(66),char(111),char(100),char(121),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117),char(108), -char(116),char(105),char(66),char(111),char(100),char(121),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117), -char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(76),char(105),char(110),char(107),char(67),char(111),char(108),char(108),char(105),char(100),char(101),char(114),char(70), -char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121), -char(76),char(105),char(110),char(107),char(67),char(111),char(108),char(108),char(105),char(100),char(101),char(114),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97), -char(116),char(97),char(0),char(0),char(84),char(76),char(69),char(78),char(1),char(0),char(1),char(0),char(2),char(0),char(2),char(0),char(4),char(0),char(4),char(0), -char(4),char(0),char(4),char(0),char(8),char(0),char(0),char(0),char(16),char(0),char(48),char(0),char(16),char(0),char(16),char(0),char(32),char(0),char(16),char(0), -char(32),char(0),char(48),char(0),char(96),char(0),char(64),char(0),char(-128),char(0),char(20),char(0),char(48),char(0),char(80),char(0),char(16),char(0),char(96),char(0), -char(-112),char(0),char(16),char(0),char(56),char(0),char(56),char(0),char(20),char(0),char(72),char(0),char(4),char(0),char(4),char(0),char(8),char(0),char(4),char(0), -char(56),char(0),char(32),char(0),char(80),char(0),char(72),char(0),char(96),char(0),char(80),char(0),char(32),char(0),char(64),char(0),char(64),char(0),char(64),char(0), -char(16),char(0),char(-8),char(5),char(-8),char(1),char(64),char(3),char(32),char(1),char(72),char(0),char(80),char(0),char(-104),char(0),char(88),char(0),char(-72),char(0), -char(104),char(0),char(8),char(2),char(-56),char(3),char(8),char(0),char(64),char(0),char(64),char(0),char(0),char(0),char(80),char(0),char(96),char(0),char(-112),char(0), +char(102),char(111),char(77),char(97),char(112),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(99),char(97),char(108),char(101),char(100),char(84),char(114), +char(105),char(97),char(110),char(103),char(108),char(101),char(77),char(101),char(115),char(104),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0), +char(98),char(116),char(67),char(111),char(109),char(112),char(111),char(117),char(110),char(100),char(83),char(104),char(97),char(112),char(101),char(67),char(104),char(105),char(108),char(100), +char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(109),char(112),char(111),char(117),char(110),char(100),char(83),char(104),char(97),char(112),char(101), +char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(121),char(108),char(105),char(110),char(100),char(101),char(114),char(83),char(104),char(97),char(112),char(101), +char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(101),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97), +char(0),char(98),char(116),char(67),char(97),char(112),char(115),char(117),char(108),char(101),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116),char(97),char(0), +char(98),char(116),char(84),char(114),char(105),char(97),char(110),char(103),char(108),char(101),char(73),char(110),char(102),char(111),char(68),char(97),char(116),char(97),char(0),char(98), +char(116),char(71),char(73),char(109),char(112),char(97),char(99),char(116),char(77),char(101),char(115),char(104),char(83),char(104),char(97),char(112),char(101),char(68),char(97),char(116), +char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(118),char(101),char(120),char(72),char(117),char(108),char(108),char(83),char(104),char(97),char(112),char(101),char(68), +char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(108),char(108),char(105),char(115),char(105),char(111),char(110),char(79),char(98),char(106),char(101),char(99), +char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(108),char(108),char(105),char(115), +char(105),char(111),char(110),char(79),char(98),char(106),char(101),char(99),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98), +char(116),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(83),char(111),char(108),char(118),char(101),char(114),char(73),char(110),char(102),char(111),char(68),char(111), +char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(116),char(97),char(99),char(116),char(83),char(111), +char(108),char(118),char(101),char(114),char(73),char(110),char(102),char(111),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116), +char(68),char(121),char(110),char(97),char(109),char(105),char(99),char(115),char(87),char(111),char(114),char(108),char(100),char(68),char(111),char(117),char(98),char(108),char(101),char(68), +char(97),char(116),char(97),char(0),char(98),char(116),char(68),char(121),char(110),char(97),char(109),char(105),char(99),char(115),char(87),char(111),char(114),char(108),char(100),char(70), +char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(82),char(105),char(103),char(105),char(100),char(66),char(111),char(100),char(121), +char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(82),char(105),char(103),char(105),char(100),char(66),char(111),char(100), +char(121),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(67),char(111),char(110),char(115),char(116),char(114), +char(97),char(105),char(110),char(116),char(73),char(110),char(102),char(111),char(49),char(0),char(98),char(116),char(84),char(121),char(112),char(101),char(100),char(67),char(111),char(110), +char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84), +char(121),char(112),char(101),char(100),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98), +char(116),char(82),char(105),char(103),char(105),char(100),char(66),char(111),char(100),char(121),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(84),char(121),char(112), +char(101),char(100),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97), +char(116),char(97),char(0),char(98),char(116),char(80),char(111),char(105),char(110),char(116),char(50),char(80),char(111),char(105),char(110),char(116),char(67),char(111),char(110),char(115), +char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(80),char(111), +char(105),char(110),char(116),char(50),char(80),char(111),char(105),char(110),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68), +char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(50),char(0),char(98),char(116),char(80),char(111),char(105),char(110),char(116),char(50),char(80), +char(111),char(105),char(110),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101), +char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(72),char(105),char(110),char(103),char(101),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105), +char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(72),char(105),char(110),char(103),char(101), +char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0), +char(98),char(116),char(72),char(105),char(110),char(103),char(101),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117), +char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(50),char(0),char(98),char(116),char(67),char(111),char(110),char(101),char(84),char(119),char(105),char(115),char(116), +char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97), +char(0),char(98),char(116),char(67),char(111),char(110),char(101),char(84),char(119),char(105),char(115),char(116),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105), +char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102), +char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(110), +char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111), +char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(50),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54), +char(68),char(111),char(102),char(83),char(112),char(114),char(105),char(110),char(103),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68), +char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(83),char(112),char(114), +char(105),char(110),char(103),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68), +char(97),char(116),char(97),char(50),char(0),char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(83),char(112), +char(114),char(105),char(110),char(103),char(50),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0), +char(98),char(116),char(71),char(101),char(110),char(101),char(114),char(105),char(99),char(54),char(68),char(111),char(102),char(83),char(112),char(114),char(105),char(110),char(103),char(50), +char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97), +char(50),char(0),char(98),char(116),char(83),char(108),char(105),char(100),char(101),char(114),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116), +char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(108),char(105),char(100),char(101),char(114),char(67),char(111),char(110),char(115),char(116),char(114),char(97), +char(105),char(110),char(116),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(71),char(101),char(97),char(114), +char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0), +char(98),char(116),char(71),char(101),char(97),char(114),char(67),char(111),char(110),char(115),char(116),char(114),char(97),char(105),char(110),char(116),char(68),char(111),char(117),char(98), +char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(77),char(97),char(116),char(101),char(114), +char(105),char(97),char(108),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(78),char(111),char(100),char(101), +char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(76),char(105),char(110),char(107),char(68),char(97),char(116), +char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(70),char(97),char(99),char(101),char(68),char(97),char(116),char(97),char(0),char(83), +char(111),char(102),char(116),char(66),char(111),char(100),char(121),char(84),char(101),char(116),char(114),char(97),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102), +char(116),char(82),char(105),char(103),char(105),char(100),char(65),char(110),char(99),char(104),char(111),char(114),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102), +char(116),char(66),char(111),char(100),char(121),char(67),char(111),char(110),char(102),char(105),char(103),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116), +char(66),char(111),char(100),char(121),char(80),char(111),char(115),char(101),char(68),char(97),char(116),char(97),char(0),char(83),char(111),char(102),char(116),char(66),char(111),char(100), +char(121),char(67),char(108),char(117),char(115),char(116),char(101),char(114),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(111),char(102),char(116),char(66), +char(111),char(100),char(121),char(74),char(111),char(105),char(110),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(83),char(111),char(102),char(116),char(66), +char(111),char(100),char(121),char(70),char(108),char(111),char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105), +char(66),char(111),char(100),char(121),char(76),char(105),char(110),char(107),char(68),char(111),char(117),char(98),char(108),char(101),char(68),char(97),char(116),char(97),char(0),char(98), +char(116),char(77),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(76),char(105),char(110),char(107),char(70),char(108),char(111),char(97),char(116),char(68), +char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(68),char(111),char(117),char(98),char(108), +char(101),char(68),char(97),char(116),char(97),char(0),char(98),char(116),char(77),char(117),char(108),char(116),char(105),char(66),char(111),char(100),char(121),char(70),char(108),char(111), +char(97),char(116),char(68),char(97),char(116),char(97),char(0),char(0),char(84),char(76),char(69),char(78),char(1),char(0),char(1),char(0),char(2),char(0),char(2),char(0), +char(4),char(0),char(4),char(0),char(4),char(0),char(4),char(0),char(8),char(0),char(0),char(0),char(16),char(0),char(48),char(0),char(16),char(0),char(16),char(0), +char(32),char(0),char(16),char(0),char(32),char(0),char(48),char(0),char(96),char(0),char(64),char(0),char(-128),char(0),char(20),char(0),char(48),char(0),char(80),char(0), +char(16),char(0),char(96),char(0),char(-112),char(0),char(16),char(0),char(56),char(0),char(56),char(0),char(20),char(0),char(72),char(0),char(4),char(0),char(4),char(0), +char(8),char(0),char(4),char(0),char(56),char(0),char(32),char(0),char(80),char(0),char(72),char(0),char(96),char(0),char(80),char(0),char(32),char(0),char(64),char(0), +char(64),char(0),char(64),char(0),char(16),char(0),char(72),char(0),char(80),char(0),char(-16),char(1),char(24),char(1),char(-104),char(0),char(88),char(0),char(-72),char(0), +char(104),char(0),char(0),char(2),char(-64),char(3),char(8),char(0),char(64),char(0),char(64),char(0),char(0),char(0),char(80),char(0),char(96),char(0),char(-112),char(0), char(-128),char(0),char(104),char(1),char(-24),char(0),char(-104),char(1),char(-120),char(1),char(-32),char(0),char(8),char(1),char(-40),char(1),char(104),char(1),char(-128),char(2), char(-112),char(2),char(-64),char(4),char(-40),char(0),char(120),char(1),char(104),char(0),char(-104),char(0),char(16),char(0),char(104),char(0),char(24),char(0),char(40),char(0), -char(104),char(0),char(96),char(0),char(104),char(0),char(-56),char(0),char(104),char(1),char(112),char(0),char(-16),char(1),char(-128),char(3),char(-40),char(1),char(-56),char(0), -char(112),char(0),char(48),char(1),char(8),char(2),char(0),char(0),char(83),char(84),char(82),char(67),char(88),char(0),char(0),char(0),char(10),char(0),char(3),char(0), -char(4),char(0),char(0),char(0),char(4),char(0),char(1),char(0),char(9),char(0),char(2),char(0),char(11),char(0),char(3),char(0),char(10),char(0),char(3),char(0), -char(10),char(0),char(4),char(0),char(10),char(0),char(5),char(0),char(12),char(0),char(2),char(0),char(9),char(0),char(6),char(0),char(9),char(0),char(7),char(0), -char(13),char(0),char(1),char(0),char(7),char(0),char(8),char(0),char(14),char(0),char(1),char(0),char(8),char(0),char(8),char(0),char(15),char(0),char(1),char(0), -char(7),char(0),char(8),char(0),char(16),char(0),char(1),char(0),char(8),char(0),char(8),char(0),char(17),char(0),char(1),char(0),char(13),char(0),char(9),char(0), -char(18),char(0),char(1),char(0),char(14),char(0),char(9),char(0),char(19),char(0),char(2),char(0),char(17),char(0),char(10),char(0),char(13),char(0),char(11),char(0), -char(20),char(0),char(2),char(0),char(18),char(0),char(10),char(0),char(14),char(0),char(11),char(0),char(21),char(0),char(4),char(0),char(4),char(0),char(12),char(0), -char(4),char(0),char(13),char(0),char(2),char(0),char(14),char(0),char(2),char(0),char(15),char(0),char(22),char(0),char(6),char(0),char(13),char(0),char(16),char(0), -char(13),char(0),char(17),char(0),char(4),char(0),char(18),char(0),char(4),char(0),char(19),char(0),char(4),char(0),char(20),char(0),char(0),char(0),char(21),char(0), -char(23),char(0),char(6),char(0),char(14),char(0),char(16),char(0),char(14),char(0),char(17),char(0),char(4),char(0),char(18),char(0),char(4),char(0),char(19),char(0), -char(4),char(0),char(20),char(0),char(0),char(0),char(21),char(0),char(24),char(0),char(3),char(0),char(2),char(0),char(14),char(0),char(2),char(0),char(15),char(0), -char(4),char(0),char(22),char(0),char(25),char(0),char(12),char(0),char(13),char(0),char(23),char(0),char(13),char(0),char(24),char(0),char(13),char(0),char(25),char(0), -char(4),char(0),char(26),char(0),char(4),char(0),char(27),char(0),char(4),char(0),char(28),char(0),char(4),char(0),char(29),char(0),char(22),char(0),char(30),char(0), -char(24),char(0),char(31),char(0),char(21),char(0),char(32),char(0),char(4),char(0),char(33),char(0),char(4),char(0),char(34),char(0),char(26),char(0),char(12),char(0), -char(14),char(0),char(23),char(0),char(14),char(0),char(24),char(0),char(14),char(0),char(25),char(0),char(4),char(0),char(26),char(0),char(4),char(0),char(27),char(0), -char(4),char(0),char(28),char(0),char(4),char(0),char(29),char(0),char(23),char(0),char(30),char(0),char(24),char(0),char(31),char(0),char(4),char(0),char(33),char(0), -char(4),char(0),char(34),char(0),char(21),char(0),char(32),char(0),char(27),char(0),char(3),char(0),char(0),char(0),char(35),char(0),char(4),char(0),char(36),char(0), -char(0),char(0),char(37),char(0),char(28),char(0),char(5),char(0),char(27),char(0),char(38),char(0),char(13),char(0),char(39),char(0),char(13),char(0),char(40),char(0), -char(7),char(0),char(41),char(0),char(0),char(0),char(21),char(0),char(29),char(0),char(5),char(0),char(27),char(0),char(38),char(0),char(13),char(0),char(39),char(0), -char(13),char(0),char(42),char(0),char(7),char(0),char(43),char(0),char(4),char(0),char(44),char(0),char(30),char(0),char(2),char(0),char(13),char(0),char(45),char(0), -char(7),char(0),char(46),char(0),char(31),char(0),char(4),char(0),char(29),char(0),char(47),char(0),char(30),char(0),char(48),char(0),char(4),char(0),char(49),char(0), -char(0),char(0),char(37),char(0),char(32),char(0),char(1),char(0),char(4),char(0),char(50),char(0),char(33),char(0),char(2),char(0),char(2),char(0),char(50),char(0), -char(0),char(0),char(51),char(0),char(34),char(0),char(2),char(0),char(2),char(0),char(52),char(0),char(0),char(0),char(51),char(0),char(35),char(0),char(2),char(0), -char(0),char(0),char(52),char(0),char(0),char(0),char(53),char(0),char(36),char(0),char(8),char(0),char(13),char(0),char(54),char(0),char(14),char(0),char(55),char(0), -char(32),char(0),char(56),char(0),char(34),char(0),char(57),char(0),char(35),char(0),char(58),char(0),char(33),char(0),char(59),char(0),char(4),char(0),char(60),char(0), -char(4),char(0),char(61),char(0),char(37),char(0),char(4),char(0),char(36),char(0),char(62),char(0),char(13),char(0),char(63),char(0),char(4),char(0),char(64),char(0), -char(0),char(0),char(37),char(0),char(38),char(0),char(7),char(0),char(27),char(0),char(38),char(0),char(37),char(0),char(65),char(0),char(25),char(0),char(66),char(0), -char(26),char(0),char(67),char(0),char(39),char(0),char(68),char(0),char(7),char(0),char(43),char(0),char(0),char(0),char(69),char(0),char(40),char(0),char(2),char(0), -char(38),char(0),char(70),char(0),char(13),char(0),char(39),char(0),char(41),char(0),char(4),char(0),char(19),char(0),char(71),char(0),char(27),char(0),char(72),char(0), -char(4),char(0),char(73),char(0),char(7),char(0),char(74),char(0),char(42),char(0),char(4),char(0),char(27),char(0),char(38),char(0),char(41),char(0),char(75),char(0), -char(4),char(0),char(76),char(0),char(7),char(0),char(43),char(0),char(43),char(0),char(3),char(0),char(29),char(0),char(47),char(0),char(4),char(0),char(77),char(0), -char(0),char(0),char(37),char(0),char(44),char(0),char(3),char(0),char(29),char(0),char(47),char(0),char(4),char(0),char(78),char(0),char(0),char(0),char(37),char(0), -char(45),char(0),char(3),char(0),char(29),char(0),char(47),char(0),char(4),char(0),char(77),char(0),char(0),char(0),char(37),char(0),char(46),char(0),char(4),char(0), -char(4),char(0),char(79),char(0),char(7),char(0),char(80),char(0),char(7),char(0),char(81),char(0),char(7),char(0),char(82),char(0),char(39),char(0),char(14),char(0), -char(4),char(0),char(83),char(0),char(4),char(0),char(84),char(0),char(46),char(0),char(85),char(0),char(4),char(0),char(86),char(0),char(7),char(0),char(87),char(0), -char(7),char(0),char(88),char(0),char(7),char(0),char(89),char(0),char(7),char(0),char(90),char(0),char(7),char(0),char(91),char(0),char(4),char(0),char(92),char(0), -char(4),char(0),char(93),char(0),char(4),char(0),char(94),char(0),char(4),char(0),char(95),char(0),char(0),char(0),char(37),char(0),char(47),char(0),char(38),char(0), -char(14),char(0),char(96),char(0),char(14),char(0),char(97),char(0),char(14),char(0),char(98),char(0),char(14),char(0),char(99),char(0),char(14),char(0),char(100),char(0), -char(14),char(0),char(101),char(0),char(14),char(0),char(102),char(0),char(8),char(0),char(103),char(0),char(8),char(0),char(104),char(0),char(8),char(0),char(105),char(0), -char(8),char(0),char(106),char(0),char(8),char(0),char(107),char(0),char(8),char(0),char(108),char(0),char(4),char(0),char(109),char(0),char(4),char(0),char(110),char(0), -char(4),char(0),char(111),char(0),char(4),char(0),char(112),char(0),char(4),char(0),char(113),char(0),char(8),char(0),char(114),char(0),char(8),char(0),char(115),char(0), -char(8),char(0),char(116),char(0),char(8),char(0),char(117),char(0),char(8),char(0),char(118),char(0),char(8),char(0),char(119),char(0),char(8),char(0),char(120),char(0), -char(8),char(0),char(121),char(0),char(8),char(0),char(122),char(0),char(4),char(0),char(123),char(0),char(4),char(0),char(124),char(0),char(4),char(0),char(125),char(0), -char(4),char(0),char(126),char(0),char(4),char(0),char(127),char(0),char(4),char(0),char(-128),char(0),char(8),char(0),char(-127),char(0),char(8),char(0),char(-126),char(0), -char(4),char(0),char(44),char(0),char(48),char(0),char(-125),char(0),char(48),char(0),char(-124),char(0),char(49),char(0),char(38),char(0),char(13),char(0),char(96),char(0), -char(13),char(0),char(97),char(0),char(13),char(0),char(98),char(0),char(13),char(0),char(99),char(0),char(13),char(0),char(100),char(0),char(13),char(0),char(101),char(0), -char(13),char(0),char(102),char(0),char(7),char(0),char(103),char(0),char(7),char(0),char(104),char(0),char(7),char(0),char(105),char(0),char(7),char(0),char(106),char(0), -char(7),char(0),char(107),char(0),char(7),char(0),char(108),char(0),char(4),char(0),char(109),char(0),char(4),char(0),char(110),char(0),char(4),char(0),char(111),char(0), -char(4),char(0),char(112),char(0),char(4),char(0),char(113),char(0),char(7),char(0),char(114),char(0),char(7),char(0),char(115),char(0),char(7),char(0),char(116),char(0), -char(7),char(0),char(117),char(0),char(7),char(0),char(118),char(0),char(7),char(0),char(119),char(0),char(7),char(0),char(120),char(0),char(7),char(0),char(121),char(0), -char(7),char(0),char(122),char(0),char(4),char(0),char(123),char(0),char(4),char(0),char(124),char(0),char(4),char(0),char(125),char(0),char(4),char(0),char(126),char(0), -char(4),char(0),char(127),char(0),char(4),char(0),char(-128),char(0),char(7),char(0),char(-127),char(0),char(7),char(0),char(-126),char(0),char(4),char(0),char(44),char(0), -char(50),char(0),char(-125),char(0),char(50),char(0),char(-124),char(0),char(51),char(0),char(5),char(0),char(27),char(0),char(38),char(0),char(37),char(0),char(65),char(0), -char(13),char(0),char(39),char(0),char(7),char(0),char(43),char(0),char(4),char(0),char(-123),char(0),char(52),char(0),char(5),char(0),char(29),char(0),char(47),char(0), -char(13),char(0),char(-122),char(0),char(14),char(0),char(-121),char(0),char(4),char(0),char(-120),char(0),char(0),char(0),char(-119),char(0),char(48),char(0),char(29),char(0), -char(9),char(0),char(-118),char(0),char(9),char(0),char(-117),char(0),char(27),char(0),char(-116),char(0),char(0),char(0),char(35),char(0),char(20),char(0),char(-115),char(0), -char(20),char(0),char(-114),char(0),char(14),char(0),char(-113),char(0),char(14),char(0),char(-112),char(0),char(14),char(0),char(-111),char(0),char(8),char(0),char(-126),char(0), -char(8),char(0),char(-110),char(0),char(8),char(0),char(-109),char(0),char(8),char(0),char(-108),char(0),char(8),char(0),char(-107),char(0),char(8),char(0),char(-106),char(0), -char(8),char(0),char(-105),char(0),char(8),char(0),char(-104),char(0),char(8),char(0),char(-103),char(0),char(8),char(0),char(-102),char(0),char(4),char(0),char(-101),char(0), -char(4),char(0),char(-100),char(0),char(4),char(0),char(-99),char(0),char(4),char(0),char(-98),char(0),char(4),char(0),char(-97),char(0),char(4),char(0),char(-96),char(0), -char(4),char(0),char(-95),char(0),char(4),char(0),char(-94),char(0),char(4),char(0),char(-93),char(0),char(4),char(0),char(-92),char(0),char(50),char(0),char(29),char(0), -char(9),char(0),char(-118),char(0),char(9),char(0),char(-117),char(0),char(27),char(0),char(-116),char(0),char(0),char(0),char(35),char(0),char(19),char(0),char(-115),char(0), -char(19),char(0),char(-114),char(0),char(13),char(0),char(-113),char(0),char(13),char(0),char(-112),char(0),char(13),char(0),char(-111),char(0),char(7),char(0),char(-126),char(0), -char(7),char(0),char(-110),char(0),char(7),char(0),char(-109),char(0),char(7),char(0),char(-108),char(0),char(7),char(0),char(-107),char(0),char(7),char(0),char(-106),char(0), -char(7),char(0),char(-105),char(0),char(7),char(0),char(-104),char(0),char(7),char(0),char(-103),char(0),char(7),char(0),char(-102),char(0),char(4),char(0),char(-101),char(0), -char(4),char(0),char(-100),char(0),char(4),char(0),char(-99),char(0),char(4),char(0),char(-98),char(0),char(4),char(0),char(-97),char(0),char(4),char(0),char(-96),char(0), -char(4),char(0),char(-95),char(0),char(4),char(0),char(-94),char(0),char(4),char(0),char(-93),char(0),char(4),char(0),char(-92),char(0),char(53),char(0),char(22),char(0), -char(8),char(0),char(-91),char(0),char(8),char(0),char(-90),char(0),char(8),char(0),char(-109),char(0),char(8),char(0),char(-89),char(0),char(8),char(0),char(-105),char(0), -char(8),char(0),char(-88),char(0),char(8),char(0),char(-87),char(0),char(8),char(0),char(-86),char(0),char(8),char(0),char(-85),char(0),char(8),char(0),char(-84),char(0), -char(8),char(0),char(-83),char(0),char(8),char(0),char(-82),char(0),char(8),char(0),char(-81),char(0),char(8),char(0),char(-80),char(0),char(8),char(0),char(-79),char(0), -char(8),char(0),char(-78),char(0),char(4),char(0),char(-77),char(0),char(4),char(0),char(-76),char(0),char(4),char(0),char(-75),char(0),char(4),char(0),char(-74),char(0), -char(4),char(0),char(-73),char(0),char(0),char(0),char(37),char(0),char(54),char(0),char(22),char(0),char(7),char(0),char(-91),char(0),char(7),char(0),char(-90),char(0), -char(7),char(0),char(-109),char(0),char(7),char(0),char(-89),char(0),char(7),char(0),char(-105),char(0),char(7),char(0),char(-88),char(0),char(7),char(0),char(-87),char(0), -char(7),char(0),char(-86),char(0),char(7),char(0),char(-85),char(0),char(7),char(0),char(-84),char(0),char(7),char(0),char(-83),char(0),char(7),char(0),char(-82),char(0), -char(7),char(0),char(-81),char(0),char(7),char(0),char(-80),char(0),char(7),char(0),char(-79),char(0),char(7),char(0),char(-78),char(0),char(4),char(0),char(-77),char(0), -char(4),char(0),char(-76),char(0),char(4),char(0),char(-75),char(0),char(4),char(0),char(-74),char(0),char(4),char(0),char(-73),char(0),char(0),char(0),char(37),char(0), -char(55),char(0),char(2),char(0),char(53),char(0),char(-72),char(0),char(14),char(0),char(-71),char(0),char(56),char(0),char(2),char(0),char(54),char(0),char(-72),char(0), -char(13),char(0),char(-71),char(0),char(57),char(0),char(21),char(0),char(50),char(0),char(-70),char(0),char(17),char(0),char(-69),char(0),char(13),char(0),char(-68),char(0), -char(13),char(0),char(-67),char(0),char(13),char(0),char(-66),char(0),char(13),char(0),char(-65),char(0),char(13),char(0),char(-71),char(0),char(13),char(0),char(-64),char(0), -char(13),char(0),char(-63),char(0),char(13),char(0),char(-62),char(0),char(13),char(0),char(-61),char(0),char(7),char(0),char(-60),char(0),char(7),char(0),char(-59),char(0), -char(7),char(0),char(-58),char(0),char(7),char(0),char(-57),char(0),char(7),char(0),char(-56),char(0),char(7),char(0),char(-55),char(0),char(7),char(0),char(-54),char(0), -char(7),char(0),char(-53),char(0),char(7),char(0),char(-52),char(0),char(4),char(0),char(-51),char(0),char(58),char(0),char(22),char(0),char(48),char(0),char(-70),char(0), -char(18),char(0),char(-69),char(0),char(14),char(0),char(-68),char(0),char(14),char(0),char(-67),char(0),char(14),char(0),char(-66),char(0),char(14),char(0),char(-65),char(0), -char(14),char(0),char(-71),char(0),char(14),char(0),char(-64),char(0),char(14),char(0),char(-63),char(0),char(14),char(0),char(-62),char(0),char(14),char(0),char(-61),char(0), -char(8),char(0),char(-60),char(0),char(8),char(0),char(-59),char(0),char(8),char(0),char(-58),char(0),char(8),char(0),char(-57),char(0),char(8),char(0),char(-56),char(0), -char(8),char(0),char(-55),char(0),char(8),char(0),char(-54),char(0),char(8),char(0),char(-53),char(0),char(8),char(0),char(-52),char(0),char(4),char(0),char(-51),char(0), -char(0),char(0),char(37),char(0),char(59),char(0),char(2),char(0),char(4),char(0),char(-50),char(0),char(4),char(0),char(-49),char(0),char(60),char(0),char(13),char(0), -char(57),char(0),char(-48),char(0),char(57),char(0),char(-47),char(0),char(0),char(0),char(35),char(0),char(4),char(0),char(-128),char(0),char(4),char(0),char(-46),char(0), -char(4),char(0),char(-45),char(0),char(4),char(0),char(-44),char(0),char(7),char(0),char(-43),char(0),char(7),char(0),char(-42),char(0),char(4),char(0),char(-41),char(0), -char(4),char(0),char(-40),char(0),char(7),char(0),char(-39),char(0),char(4),char(0),char(-38),char(0),char(61),char(0),char(13),char(0),char(62),char(0),char(-48),char(0), -char(62),char(0),char(-47),char(0),char(0),char(0),char(35),char(0),char(4),char(0),char(-128),char(0),char(4),char(0),char(-46),char(0),char(4),char(0),char(-45),char(0), -char(4),char(0),char(-44),char(0),char(7),char(0),char(-43),char(0),char(7),char(0),char(-42),char(0),char(4),char(0),char(-41),char(0),char(4),char(0),char(-40),char(0), -char(7),char(0),char(-39),char(0),char(4),char(0),char(-38),char(0),char(63),char(0),char(14),char(0),char(58),char(0),char(-48),char(0),char(58),char(0),char(-47),char(0), -char(0),char(0),char(35),char(0),char(4),char(0),char(-128),char(0),char(4),char(0),char(-46),char(0),char(4),char(0),char(-45),char(0),char(4),char(0),char(-44),char(0), -char(8),char(0),char(-43),char(0),char(8),char(0),char(-42),char(0),char(4),char(0),char(-41),char(0),char(4),char(0),char(-40),char(0),char(8),char(0),char(-39),char(0), -char(4),char(0),char(-38),char(0),char(0),char(0),char(-37),char(0),char(64),char(0),char(3),char(0),char(61),char(0),char(-36),char(0),char(13),char(0),char(-35),char(0), -char(13),char(0),char(-34),char(0),char(65),char(0),char(3),char(0),char(63),char(0),char(-36),char(0),char(14),char(0),char(-35),char(0),char(14),char(0),char(-34),char(0), -char(66),char(0),char(3),char(0),char(61),char(0),char(-36),char(0),char(14),char(0),char(-35),char(0),char(14),char(0),char(-34),char(0),char(67),char(0),char(13),char(0), -char(61),char(0),char(-36),char(0),char(20),char(0),char(-33),char(0),char(20),char(0),char(-32),char(0),char(4),char(0),char(-31),char(0),char(4),char(0),char(-30),char(0), -char(4),char(0),char(-29),char(0),char(7),char(0),char(-28),char(0),char(7),char(0),char(-27),char(0),char(7),char(0),char(-26),char(0),char(7),char(0),char(-25),char(0), -char(7),char(0),char(-24),char(0),char(7),char(0),char(-23),char(0),char(7),char(0),char(-22),char(0),char(68),char(0),char(13),char(0),char(61),char(0),char(-36),char(0), -char(19),char(0),char(-33),char(0),char(19),char(0),char(-32),char(0),char(4),char(0),char(-31),char(0),char(4),char(0),char(-30),char(0),char(4),char(0),char(-29),char(0), -char(7),char(0),char(-28),char(0),char(7),char(0),char(-27),char(0),char(7),char(0),char(-26),char(0),char(7),char(0),char(-25),char(0),char(7),char(0),char(-24),char(0), -char(7),char(0),char(-23),char(0),char(7),char(0),char(-22),char(0),char(69),char(0),char(14),char(0),char(63),char(0),char(-36),char(0),char(20),char(0),char(-33),char(0), -char(20),char(0),char(-32),char(0),char(4),char(0),char(-31),char(0),char(4),char(0),char(-30),char(0),char(4),char(0),char(-29),char(0),char(8),char(0),char(-28),char(0), -char(8),char(0),char(-27),char(0),char(8),char(0),char(-26),char(0),char(8),char(0),char(-25),char(0),char(8),char(0),char(-24),char(0),char(8),char(0),char(-23),char(0), -char(8),char(0),char(-22),char(0),char(0),char(0),char(-21),char(0),char(70),char(0),char(10),char(0),char(63),char(0),char(-36),char(0),char(20),char(0),char(-33),char(0), -char(20),char(0),char(-32),char(0),char(8),char(0),char(-20),char(0),char(8),char(0),char(-19),char(0),char(8),char(0),char(-18),char(0),char(8),char(0),char(-24),char(0), -char(8),char(0),char(-23),char(0),char(8),char(0),char(-22),char(0),char(8),char(0),char(-90),char(0),char(71),char(0),char(11),char(0),char(61),char(0),char(-36),char(0), -char(19),char(0),char(-33),char(0),char(19),char(0),char(-32),char(0),char(7),char(0),char(-20),char(0),char(7),char(0),char(-19),char(0),char(7),char(0),char(-18),char(0), -char(7),char(0),char(-24),char(0),char(7),char(0),char(-23),char(0),char(7),char(0),char(-22),char(0),char(7),char(0),char(-90),char(0),char(0),char(0),char(21),char(0), -char(72),char(0),char(9),char(0),char(61),char(0),char(-36),char(0),char(19),char(0),char(-33),char(0),char(19),char(0),char(-32),char(0),char(13),char(0),char(-17),char(0), -char(13),char(0),char(-16),char(0),char(13),char(0),char(-15),char(0),char(13),char(0),char(-14),char(0),char(4),char(0),char(-13),char(0),char(4),char(0),char(-12),char(0), -char(73),char(0),char(9),char(0),char(63),char(0),char(-36),char(0),char(20),char(0),char(-33),char(0),char(20),char(0),char(-32),char(0),char(14),char(0),char(-17),char(0), -char(14),char(0),char(-16),char(0),char(14),char(0),char(-15),char(0),char(14),char(0),char(-14),char(0),char(4),char(0),char(-13),char(0),char(4),char(0),char(-12),char(0), -char(74),char(0),char(5),char(0),char(72),char(0),char(-11),char(0),char(4),char(0),char(-10),char(0),char(7),char(0),char(-9),char(0),char(7),char(0),char(-8),char(0), -char(7),char(0),char(-7),char(0),char(75),char(0),char(5),char(0),char(73),char(0),char(-11),char(0),char(4),char(0),char(-10),char(0),char(8),char(0),char(-9),char(0), -char(8),char(0),char(-8),char(0),char(8),char(0),char(-7),char(0),char(76),char(0),char(41),char(0),char(61),char(0),char(-36),char(0),char(19),char(0),char(-33),char(0), -char(19),char(0),char(-32),char(0),char(13),char(0),char(-17),char(0),char(13),char(0),char(-16),char(0),char(13),char(0),char(-6),char(0),char(13),char(0),char(-5),char(0), -char(13),char(0),char(-4),char(0),char(13),char(0),char(-3),char(0),char(13),char(0),char(-2),char(0),char(13),char(0),char(-1),char(0),char(13),char(0),char(0),char(1), -char(13),char(0),char(1),char(1),char(13),char(0),char(2),char(1),char(13),char(0),char(3),char(1),char(13),char(0),char(4),char(1),char(0),char(0),char(5),char(1), -char(0),char(0),char(6),char(1),char(0),char(0),char(7),char(1),char(0),char(0),char(8),char(1),char(0),char(0),char(9),char(1),char(0),char(0),char(-21),char(0), -char(13),char(0),char(-15),char(0),char(13),char(0),char(-14),char(0),char(13),char(0),char(10),char(1),char(13),char(0),char(11),char(1),char(13),char(0),char(12),char(1), -char(13),char(0),char(13),char(1),char(13),char(0),char(14),char(1),char(13),char(0),char(15),char(1),char(13),char(0),char(16),char(1),char(13),char(0),char(17),char(1), -char(13),char(0),char(18),char(1),char(13),char(0),char(19),char(1),char(13),char(0),char(20),char(1),char(0),char(0),char(21),char(1),char(0),char(0),char(22),char(1), -char(0),char(0),char(23),char(1),char(0),char(0),char(24),char(1),char(0),char(0),char(25),char(1),char(4),char(0),char(26),char(1),char(77),char(0),char(41),char(0), -char(63),char(0),char(-36),char(0),char(20),char(0),char(-33),char(0),char(20),char(0),char(-32),char(0),char(14),char(0),char(-17),char(0),char(14),char(0),char(-16),char(0), -char(14),char(0),char(-6),char(0),char(14),char(0),char(-5),char(0),char(14),char(0),char(-4),char(0),char(14),char(0),char(-3),char(0),char(14),char(0),char(-2),char(0), -char(14),char(0),char(-1),char(0),char(14),char(0),char(0),char(1),char(14),char(0),char(1),char(1),char(14),char(0),char(2),char(1),char(14),char(0),char(3),char(1), -char(14),char(0),char(4),char(1),char(0),char(0),char(5),char(1),char(0),char(0),char(6),char(1),char(0),char(0),char(7),char(1),char(0),char(0),char(8),char(1), -char(0),char(0),char(9),char(1),char(0),char(0),char(-21),char(0),char(14),char(0),char(-15),char(0),char(14),char(0),char(-14),char(0),char(14),char(0),char(10),char(1), -char(14),char(0),char(11),char(1),char(14),char(0),char(12),char(1),char(14),char(0),char(13),char(1),char(14),char(0),char(14),char(1),char(14),char(0),char(15),char(1), -char(14),char(0),char(16),char(1),char(14),char(0),char(17),char(1),char(14),char(0),char(18),char(1),char(14),char(0),char(19),char(1),char(14),char(0),char(20),char(1), -char(0),char(0),char(21),char(1),char(0),char(0),char(22),char(1),char(0),char(0),char(23),char(1),char(0),char(0),char(24),char(1),char(0),char(0),char(25),char(1), -char(4),char(0),char(26),char(1),char(78),char(0),char(9),char(0),char(61),char(0),char(-36),char(0),char(19),char(0),char(-33),char(0),char(19),char(0),char(-32),char(0), -char(7),char(0),char(-17),char(0),char(7),char(0),char(-16),char(0),char(7),char(0),char(-15),char(0),char(7),char(0),char(-14),char(0),char(4),char(0),char(-13),char(0), -char(4),char(0),char(-12),char(0),char(79),char(0),char(9),char(0),char(63),char(0),char(-36),char(0),char(20),char(0),char(-33),char(0),char(20),char(0),char(-32),char(0), -char(8),char(0),char(-17),char(0),char(8),char(0),char(-16),char(0),char(8),char(0),char(-15),char(0),char(8),char(0),char(-14),char(0),char(4),char(0),char(-13),char(0), -char(4),char(0),char(-12),char(0),char(80),char(0),char(5),char(0),char(60),char(0),char(-36),char(0),char(13),char(0),char(27),char(1),char(13),char(0),char(28),char(1), -char(7),char(0),char(29),char(1),char(0),char(0),char(37),char(0),char(81),char(0),char(4),char(0),char(63),char(0),char(-36),char(0),char(14),char(0),char(27),char(1), -char(14),char(0),char(28),char(1),char(8),char(0),char(29),char(1),char(82),char(0),char(4),char(0),char(7),char(0),char(30),char(1),char(7),char(0),char(31),char(1), -char(7),char(0),char(32),char(1),char(4),char(0),char(79),char(0),char(83),char(0),char(10),char(0),char(82),char(0),char(33),char(1),char(13),char(0),char(34),char(1), -char(13),char(0),char(35),char(1),char(13),char(0),char(36),char(1),char(13),char(0),char(37),char(1),char(13),char(0),char(38),char(1),char(7),char(0),char(-60),char(0), -char(7),char(0),char(39),char(1),char(4),char(0),char(40),char(1),char(4),char(0),char(53),char(0),char(84),char(0),char(4),char(0),char(82),char(0),char(33),char(1), -char(4),char(0),char(41),char(1),char(7),char(0),char(42),char(1),char(4),char(0),char(43),char(1),char(85),char(0),char(4),char(0),char(13),char(0),char(38),char(1), -char(82),char(0),char(33),char(1),char(4),char(0),char(44),char(1),char(7),char(0),char(45),char(1),char(86),char(0),char(7),char(0),char(13),char(0),char(46),char(1), -char(82),char(0),char(33),char(1),char(4),char(0),char(47),char(1),char(7),char(0),char(48),char(1),char(7),char(0),char(49),char(1),char(7),char(0),char(50),char(1), -char(4),char(0),char(53),char(0),char(87),char(0),char(6),char(0),char(17),char(0),char(51),char(1),char(13),char(0),char(49),char(1),char(13),char(0),char(52),char(1), -char(62),char(0),char(53),char(1),char(4),char(0),char(54),char(1),char(7),char(0),char(50),char(1),char(88),char(0),char(26),char(0),char(4),char(0),char(55),char(1), -char(7),char(0),char(56),char(1),char(7),char(0),char(-90),char(0),char(7),char(0),char(57),char(1),char(7),char(0),char(58),char(1),char(7),char(0),char(59),char(1), -char(7),char(0),char(60),char(1),char(7),char(0),char(61),char(1),char(7),char(0),char(62),char(1),char(7),char(0),char(63),char(1),char(7),char(0),char(64),char(1), -char(7),char(0),char(65),char(1),char(7),char(0),char(66),char(1),char(7),char(0),char(67),char(1),char(7),char(0),char(68),char(1),char(7),char(0),char(69),char(1), -char(7),char(0),char(70),char(1),char(7),char(0),char(71),char(1),char(7),char(0),char(72),char(1),char(7),char(0),char(73),char(1),char(7),char(0),char(74),char(1), -char(4),char(0),char(75),char(1),char(4),char(0),char(76),char(1),char(4),char(0),char(77),char(1),char(4),char(0),char(78),char(1),char(4),char(0),char(-100),char(0), -char(89),char(0),char(12),char(0),char(17),char(0),char(79),char(1),char(17),char(0),char(80),char(1),char(17),char(0),char(81),char(1),char(13),char(0),char(82),char(1), -char(13),char(0),char(83),char(1),char(7),char(0),char(84),char(1),char(4),char(0),char(85),char(1),char(4),char(0),char(86),char(1),char(4),char(0),char(87),char(1), -char(4),char(0),char(88),char(1),char(7),char(0),char(48),char(1),char(4),char(0),char(53),char(0),char(90),char(0),char(27),char(0),char(19),char(0),char(89),char(1), -char(17),char(0),char(90),char(1),char(17),char(0),char(91),char(1),char(13),char(0),char(82),char(1),char(13),char(0),char(92),char(1),char(13),char(0),char(93),char(1), -char(13),char(0),char(94),char(1),char(13),char(0),char(95),char(1),char(13),char(0),char(96),char(1),char(4),char(0),char(97),char(1),char(7),char(0),char(98),char(1), -char(4),char(0),char(99),char(1),char(4),char(0),char(100),char(1),char(4),char(0),char(101),char(1),char(7),char(0),char(102),char(1),char(7),char(0),char(103),char(1), -char(4),char(0),char(104),char(1),char(4),char(0),char(105),char(1),char(7),char(0),char(106),char(1),char(7),char(0),char(107),char(1),char(7),char(0),char(108),char(1), -char(7),char(0),char(109),char(1),char(7),char(0),char(110),char(1),char(7),char(0),char(111),char(1),char(4),char(0),char(112),char(1),char(4),char(0),char(113),char(1), -char(4),char(0),char(114),char(1),char(91),char(0),char(12),char(0),char(9),char(0),char(115),char(1),char(9),char(0),char(116),char(1),char(13),char(0),char(117),char(1), -char(7),char(0),char(118),char(1),char(7),char(0),char(-86),char(0),char(7),char(0),char(119),char(1),char(4),char(0),char(120),char(1),char(13),char(0),char(121),char(1), -char(4),char(0),char(122),char(1),char(4),char(0),char(123),char(1),char(4),char(0),char(124),char(1),char(4),char(0),char(53),char(0),char(92),char(0),char(19),char(0), -char(50),char(0),char(-70),char(0),char(89),char(0),char(125),char(1),char(82),char(0),char(126),char(1),char(83),char(0),char(127),char(1),char(84),char(0),char(-128),char(1), -char(85),char(0),char(-127),char(1),char(86),char(0),char(-126),char(1),char(87),char(0),char(-125),char(1),char(90),char(0),char(-124),char(1),char(91),char(0),char(-123),char(1), -char(4),char(0),char(-122),char(1),char(4),char(0),char(100),char(1),char(4),char(0),char(-121),char(1),char(4),char(0),char(-120),char(1),char(4),char(0),char(-119),char(1), -char(4),char(0),char(-118),char(1),char(4),char(0),char(-117),char(1),char(4),char(0),char(-116),char(1),char(88),char(0),char(-115),char(1),char(93),char(0),char(28),char(0), -char(16),char(0),char(-114),char(1),char(14),char(0),char(-113),char(1),char(14),char(0),char(-112),char(1),char(14),char(0),char(-111),char(1),char(14),char(0),char(-110),char(1), -char(14),char(0),char(-109),char(1),char(14),char(0),char(-108),char(1),char(14),char(0),char(-107),char(1),char(14),char(0),char(-106),char(1),char(14),char(0),char(-105),char(1), -char(8),char(0),char(-104),char(1),char(4),char(0),char(-103),char(1),char(4),char(0),char(124),char(1),char(4),char(0),char(-102),char(1),char(4),char(0),char(-101),char(1), -char(8),char(0),char(-100),char(1),char(8),char(0),char(-99),char(1),char(8),char(0),char(-98),char(1),char(8),char(0),char(-97),char(1),char(8),char(0),char(-96),char(1), -char(8),char(0),char(-95),char(1),char(8),char(0),char(-94),char(1),char(8),char(0),char(-93),char(1),char(8),char(0),char(-92),char(1),char(0),char(0),char(-91),char(1), -char(0),char(0),char(-90),char(1),char(48),char(0),char(-89),char(1),char(0),char(0),char(-88),char(1),char(94),char(0),char(28),char(0),char(15),char(0),char(-114),char(1), -char(13),char(0),char(-113),char(1),char(13),char(0),char(-112),char(1),char(13),char(0),char(-111),char(1),char(13),char(0),char(-110),char(1),char(13),char(0),char(-109),char(1), -char(13),char(0),char(-108),char(1),char(13),char(0),char(-107),char(1),char(13),char(0),char(-106),char(1),char(13),char(0),char(-105),char(1),char(4),char(0),char(-102),char(1), -char(7),char(0),char(-104),char(1),char(4),char(0),char(-103),char(1),char(4),char(0),char(124),char(1),char(7),char(0),char(-100),char(1),char(7),char(0),char(-99),char(1), -char(7),char(0),char(-98),char(1),char(4),char(0),char(-101),char(1),char(7),char(0),char(-97),char(1),char(7),char(0),char(-96),char(1),char(7),char(0),char(-95),char(1), -char(7),char(0),char(-94),char(1),char(7),char(0),char(-93),char(1),char(7),char(0),char(-92),char(1),char(0),char(0),char(-91),char(1),char(0),char(0),char(-90),char(1), -char(50),char(0),char(-89),char(1),char(0),char(0),char(-88),char(1),char(95),char(0),char(11),char(0),char(14),char(0),char(-87),char(1),char(16),char(0),char(-86),char(1), -char(14),char(0),char(-85),char(1),char(14),char(0),char(-84),char(1),char(14),char(0),char(-83),char(1),char(8),char(0),char(-82),char(1),char(4),char(0),char(-121),char(1), -char(0),char(0),char(37),char(0),char(0),char(0),char(-81),char(1),char(93),char(0),char(-128),char(1),char(48),char(0),char(-80),char(1),char(96),char(0),char(10),char(0), -char(13),char(0),char(-87),char(1),char(15),char(0),char(-86),char(1),char(13),char(0),char(-85),char(1),char(13),char(0),char(-84),char(1),char(13),char(0),char(-83),char(1), -char(7),char(0),char(-82),char(1),char(4),char(0),char(-121),char(1),char(0),char(0),char(-81),char(1),char(94),char(0),char(-128),char(1),char(50),char(0),char(-80),char(1), -char(97),char(0),char(4),char(0),char(50),char(0),char(-79),char(1),char(96),char(0),char(-78),char(1),char(4),char(0),char(-77),char(1),char(0),char(0),char(37),char(0), -char(98),char(0),char(4),char(0),char(48),char(0),char(-79),char(1),char(95),char(0),char(-78),char(1),char(4),char(0),char(-77),char(1),char(0),char(0),char(37),char(0), -}; +char(104),char(0),char(96),char(0),char(104),char(0),char(-56),char(0),char(104),char(1),char(112),char(0),char(-24),char(1),char(0),char(3),char(-104),char(1),char(-48),char(0), +char(112),char(0),char(0),char(0),char(83),char(84),char(82),char(67),char(84),char(0),char(0),char(0),char(10),char(0),char(3),char(0),char(4),char(0),char(0),char(0), +char(4),char(0),char(1),char(0),char(9),char(0),char(2),char(0),char(11),char(0),char(3),char(0),char(10),char(0),char(3),char(0),char(10),char(0),char(4),char(0), +char(10),char(0),char(5),char(0),char(12),char(0),char(2),char(0),char(9),char(0),char(6),char(0),char(9),char(0),char(7),char(0),char(13),char(0),char(1),char(0), +char(7),char(0),char(8),char(0),char(14),char(0),char(1),char(0),char(8),char(0),char(8),char(0),char(15),char(0),char(1),char(0),char(7),char(0),char(8),char(0), +char(16),char(0),char(1),char(0),char(8),char(0),char(8),char(0),char(17),char(0),char(1),char(0),char(13),char(0),char(9),char(0),char(18),char(0),char(1),char(0), +char(14),char(0),char(9),char(0),char(19),char(0),char(2),char(0),char(17),char(0),char(10),char(0),char(13),char(0),char(11),char(0),char(20),char(0),char(2),char(0), +char(18),char(0),char(10),char(0),char(14),char(0),char(11),char(0),char(21),char(0),char(4),char(0),char(4),char(0),char(12),char(0),char(4),char(0),char(13),char(0), +char(2),char(0),char(14),char(0),char(2),char(0),char(15),char(0),char(22),char(0),char(6),char(0),char(13),char(0),char(16),char(0),char(13),char(0),char(17),char(0), +char(4),char(0),char(18),char(0),char(4),char(0),char(19),char(0),char(4),char(0),char(20),char(0),char(0),char(0),char(21),char(0),char(23),char(0),char(6),char(0), +char(14),char(0),char(16),char(0),char(14),char(0),char(17),char(0),char(4),char(0),char(18),char(0),char(4),char(0),char(19),char(0),char(4),char(0),char(20),char(0), +char(0),char(0),char(21),char(0),char(24),char(0),char(3),char(0),char(2),char(0),char(14),char(0),char(2),char(0),char(15),char(0),char(4),char(0),char(22),char(0), +char(25),char(0),char(12),char(0),char(13),char(0),char(23),char(0),char(13),char(0),char(24),char(0),char(13),char(0),char(25),char(0),char(4),char(0),char(26),char(0), +char(4),char(0),char(27),char(0),char(4),char(0),char(28),char(0),char(4),char(0),char(29),char(0),char(22),char(0),char(30),char(0),char(24),char(0),char(31),char(0), +char(21),char(0),char(32),char(0),char(4),char(0),char(33),char(0),char(4),char(0),char(34),char(0),char(26),char(0),char(12),char(0),char(14),char(0),char(23),char(0), +char(14),char(0),char(24),char(0),char(14),char(0),char(25),char(0),char(4),char(0),char(26),char(0),char(4),char(0),char(27),char(0),char(4),char(0),char(28),char(0), +char(4),char(0),char(29),char(0),char(23),char(0),char(30),char(0),char(24),char(0),char(31),char(0),char(4),char(0),char(33),char(0),char(4),char(0),char(34),char(0), +char(21),char(0),char(32),char(0),char(27),char(0),char(3),char(0),char(0),char(0),char(35),char(0),char(4),char(0),char(36),char(0),char(0),char(0),char(37),char(0), +char(28),char(0),char(5),char(0),char(27),char(0),char(38),char(0),char(13),char(0),char(39),char(0),char(13),char(0),char(40),char(0),char(7),char(0),char(41),char(0), +char(0),char(0),char(21),char(0),char(29),char(0),char(5),char(0),char(27),char(0),char(38),char(0),char(13),char(0),char(39),char(0),char(13),char(0),char(42),char(0), +char(7),char(0),char(43),char(0),char(4),char(0),char(44),char(0),char(30),char(0),char(2),char(0),char(13),char(0),char(45),char(0),char(7),char(0),char(46),char(0), +char(31),char(0),char(4),char(0),char(29),char(0),char(47),char(0),char(30),char(0),char(48),char(0),char(4),char(0),char(49),char(0),char(0),char(0),char(37),char(0), +char(32),char(0),char(1),char(0),char(4),char(0),char(50),char(0),char(33),char(0),char(2),char(0),char(2),char(0),char(50),char(0),char(0),char(0),char(51),char(0), +char(34),char(0),char(2),char(0),char(2),char(0),char(52),char(0),char(0),char(0),char(51),char(0),char(35),char(0),char(2),char(0),char(0),char(0),char(52),char(0), +char(0),char(0),char(53),char(0),char(36),char(0),char(8),char(0),char(13),char(0),char(54),char(0),char(14),char(0),char(55),char(0),char(32),char(0),char(56),char(0), +char(34),char(0),char(57),char(0),char(35),char(0),char(58),char(0),char(33),char(0),char(59),char(0),char(4),char(0),char(60),char(0),char(4),char(0),char(61),char(0), +char(37),char(0),char(4),char(0),char(36),char(0),char(62),char(0),char(13),char(0),char(63),char(0),char(4),char(0),char(64),char(0),char(0),char(0),char(37),char(0), +char(38),char(0),char(7),char(0),char(27),char(0),char(38),char(0),char(37),char(0),char(65),char(0),char(25),char(0),char(66),char(0),char(26),char(0),char(67),char(0), +char(39),char(0),char(68),char(0),char(7),char(0),char(43),char(0),char(0),char(0),char(69),char(0),char(40),char(0),char(2),char(0),char(38),char(0),char(70),char(0), +char(13),char(0),char(39),char(0),char(41),char(0),char(4),char(0),char(19),char(0),char(71),char(0),char(27),char(0),char(72),char(0),char(4),char(0),char(73),char(0), +char(7),char(0),char(74),char(0),char(42),char(0),char(4),char(0),char(27),char(0),char(38),char(0),char(41),char(0),char(75),char(0),char(4),char(0),char(76),char(0), +char(7),char(0),char(43),char(0),char(43),char(0),char(3),char(0),char(29),char(0),char(47),char(0),char(4),char(0),char(77),char(0),char(0),char(0),char(37),char(0), +char(44),char(0),char(3),char(0),char(29),char(0),char(47),char(0),char(4),char(0),char(78),char(0),char(0),char(0),char(37),char(0),char(45),char(0),char(3),char(0), +char(29),char(0),char(47),char(0),char(4),char(0),char(77),char(0),char(0),char(0),char(37),char(0),char(46),char(0),char(4),char(0),char(4),char(0),char(79),char(0), +char(7),char(0),char(80),char(0),char(7),char(0),char(81),char(0),char(7),char(0),char(82),char(0),char(39),char(0),char(14),char(0),char(4),char(0),char(83),char(0), +char(4),char(0),char(84),char(0),char(46),char(0),char(85),char(0),char(4),char(0),char(86),char(0),char(7),char(0),char(87),char(0),char(7),char(0),char(88),char(0), +char(7),char(0),char(89),char(0),char(7),char(0),char(90),char(0),char(7),char(0),char(91),char(0),char(4),char(0),char(92),char(0),char(4),char(0),char(93),char(0), +char(4),char(0),char(94),char(0),char(4),char(0),char(95),char(0),char(0),char(0),char(37),char(0),char(47),char(0),char(5),char(0),char(27),char(0),char(38),char(0), +char(37),char(0),char(65),char(0),char(13),char(0),char(39),char(0),char(7),char(0),char(43),char(0),char(4),char(0),char(96),char(0),char(48),char(0),char(5),char(0), +char(29),char(0),char(47),char(0),char(13),char(0),char(97),char(0),char(14),char(0),char(98),char(0),char(4),char(0),char(99),char(0),char(0),char(0),char(100),char(0), +char(49),char(0),char(27),char(0),char(9),char(0),char(101),char(0),char(9),char(0),char(102),char(0),char(27),char(0),char(103),char(0),char(0),char(0),char(35),char(0), +char(20),char(0),char(104),char(0),char(20),char(0),char(105),char(0),char(14),char(0),char(106),char(0),char(14),char(0),char(107),char(0),char(14),char(0),char(108),char(0), +char(8),char(0),char(109),char(0),char(8),char(0),char(110),char(0),char(8),char(0),char(111),char(0),char(8),char(0),char(112),char(0),char(8),char(0),char(113),char(0), +char(8),char(0),char(114),char(0),char(8),char(0),char(115),char(0),char(8),char(0),char(116),char(0),char(8),char(0),char(117),char(0),char(8),char(0),char(118),char(0), +char(4),char(0),char(119),char(0),char(4),char(0),char(120),char(0),char(4),char(0),char(121),char(0),char(4),char(0),char(122),char(0),char(4),char(0),char(123),char(0), +char(4),char(0),char(124),char(0),char(4),char(0),char(125),char(0),char(0),char(0),char(37),char(0),char(50),char(0),char(27),char(0),char(9),char(0),char(101),char(0), +char(9),char(0),char(102),char(0),char(27),char(0),char(103),char(0),char(0),char(0),char(35),char(0),char(19),char(0),char(104),char(0),char(19),char(0),char(105),char(0), +char(13),char(0),char(106),char(0),char(13),char(0),char(107),char(0),char(13),char(0),char(108),char(0),char(7),char(0),char(109),char(0),char(7),char(0),char(110),char(0), +char(7),char(0),char(111),char(0),char(7),char(0),char(112),char(0),char(7),char(0),char(113),char(0),char(7),char(0),char(114),char(0),char(7),char(0),char(115),char(0), +char(7),char(0),char(116),char(0),char(7),char(0),char(117),char(0),char(7),char(0),char(118),char(0),char(4),char(0),char(119),char(0),char(4),char(0),char(120),char(0), +char(4),char(0),char(121),char(0),char(4),char(0),char(122),char(0),char(4),char(0),char(123),char(0),char(4),char(0),char(124),char(0),char(4),char(0),char(125),char(0), +char(0),char(0),char(37),char(0),char(51),char(0),char(22),char(0),char(8),char(0),char(126),char(0),char(8),char(0),char(127),char(0),char(8),char(0),char(111),char(0), +char(8),char(0),char(-128),char(0),char(8),char(0),char(115),char(0),char(8),char(0),char(-127),char(0),char(8),char(0),char(-126),char(0),char(8),char(0),char(-125),char(0), +char(8),char(0),char(-124),char(0),char(8),char(0),char(-123),char(0),char(8),char(0),char(-122),char(0),char(8),char(0),char(-121),char(0),char(8),char(0),char(-120),char(0), +char(8),char(0),char(-119),char(0),char(8),char(0),char(-118),char(0),char(8),char(0),char(-117),char(0),char(4),char(0),char(-116),char(0),char(4),char(0),char(-115),char(0), +char(4),char(0),char(-114),char(0),char(4),char(0),char(-113),char(0),char(4),char(0),char(-112),char(0),char(0),char(0),char(37),char(0),char(52),char(0),char(22),char(0), +char(7),char(0),char(126),char(0),char(7),char(0),char(127),char(0),char(7),char(0),char(111),char(0),char(7),char(0),char(-128),char(0),char(7),char(0),char(115),char(0), +char(7),char(0),char(-127),char(0),char(7),char(0),char(-126),char(0),char(7),char(0),char(-125),char(0),char(7),char(0),char(-124),char(0),char(7),char(0),char(-123),char(0), +char(7),char(0),char(-122),char(0),char(7),char(0),char(-121),char(0),char(7),char(0),char(-120),char(0),char(7),char(0),char(-119),char(0),char(7),char(0),char(-118),char(0), +char(7),char(0),char(-117),char(0),char(4),char(0),char(-116),char(0),char(4),char(0),char(-115),char(0),char(4),char(0),char(-114),char(0),char(4),char(0),char(-113),char(0), +char(4),char(0),char(-112),char(0),char(0),char(0),char(37),char(0),char(53),char(0),char(2),char(0),char(51),char(0),char(-111),char(0),char(14),char(0),char(-110),char(0), +char(54),char(0),char(2),char(0),char(52),char(0),char(-111),char(0),char(13),char(0),char(-110),char(0),char(55),char(0),char(21),char(0),char(50),char(0),char(-109),char(0), +char(17),char(0),char(-108),char(0),char(13),char(0),char(-107),char(0),char(13),char(0),char(-106),char(0),char(13),char(0),char(-105),char(0),char(13),char(0),char(-104),char(0), +char(13),char(0),char(-110),char(0),char(13),char(0),char(-103),char(0),char(13),char(0),char(-102),char(0),char(13),char(0),char(-101),char(0),char(13),char(0),char(-100),char(0), +char(7),char(0),char(-99),char(0),char(7),char(0),char(-98),char(0),char(7),char(0),char(-97),char(0),char(7),char(0),char(-96),char(0),char(7),char(0),char(-95),char(0), +char(7),char(0),char(-94),char(0),char(7),char(0),char(-93),char(0),char(7),char(0),char(-92),char(0),char(7),char(0),char(-91),char(0),char(4),char(0),char(-90),char(0), +char(56),char(0),char(22),char(0),char(49),char(0),char(-109),char(0),char(18),char(0),char(-108),char(0),char(14),char(0),char(-107),char(0),char(14),char(0),char(-106),char(0), +char(14),char(0),char(-105),char(0),char(14),char(0),char(-104),char(0),char(14),char(0),char(-110),char(0),char(14),char(0),char(-103),char(0),char(14),char(0),char(-102),char(0), +char(14),char(0),char(-101),char(0),char(14),char(0),char(-100),char(0),char(8),char(0),char(-99),char(0),char(8),char(0),char(-98),char(0),char(8),char(0),char(-97),char(0), +char(8),char(0),char(-96),char(0),char(8),char(0),char(-95),char(0),char(8),char(0),char(-94),char(0),char(8),char(0),char(-93),char(0),char(8),char(0),char(-92),char(0), +char(8),char(0),char(-91),char(0),char(4),char(0),char(-90),char(0),char(0),char(0),char(37),char(0),char(57),char(0),char(2),char(0),char(4),char(0),char(-89),char(0), +char(4),char(0),char(-88),char(0),char(58),char(0),char(13),char(0),char(55),char(0),char(-87),char(0),char(55),char(0),char(-86),char(0),char(0),char(0),char(35),char(0), +char(4),char(0),char(-85),char(0),char(4),char(0),char(-84),char(0),char(4),char(0),char(-83),char(0),char(4),char(0),char(-82),char(0),char(7),char(0),char(-81),char(0), +char(7),char(0),char(-80),char(0),char(4),char(0),char(-79),char(0),char(4),char(0),char(-78),char(0),char(7),char(0),char(-77),char(0),char(4),char(0),char(-76),char(0), +char(59),char(0),char(13),char(0),char(60),char(0),char(-87),char(0),char(60),char(0),char(-86),char(0),char(0),char(0),char(35),char(0),char(4),char(0),char(-85),char(0), +char(4),char(0),char(-84),char(0),char(4),char(0),char(-83),char(0),char(4),char(0),char(-82),char(0),char(7),char(0),char(-81),char(0),char(7),char(0),char(-80),char(0), +char(4),char(0),char(-79),char(0),char(4),char(0),char(-78),char(0),char(7),char(0),char(-77),char(0),char(4),char(0),char(-76),char(0),char(61),char(0),char(14),char(0), +char(56),char(0),char(-87),char(0),char(56),char(0),char(-86),char(0),char(0),char(0),char(35),char(0),char(4),char(0),char(-85),char(0),char(4),char(0),char(-84),char(0), +char(4),char(0),char(-83),char(0),char(4),char(0),char(-82),char(0),char(8),char(0),char(-81),char(0),char(8),char(0),char(-80),char(0),char(4),char(0),char(-79),char(0), +char(4),char(0),char(-78),char(0),char(8),char(0),char(-77),char(0),char(4),char(0),char(-76),char(0),char(0),char(0),char(-75),char(0),char(62),char(0),char(3),char(0), +char(59),char(0),char(-74),char(0),char(13),char(0),char(-73),char(0),char(13),char(0),char(-72),char(0),char(63),char(0),char(3),char(0),char(61),char(0),char(-74),char(0), +char(14),char(0),char(-73),char(0),char(14),char(0),char(-72),char(0),char(64),char(0),char(3),char(0),char(59),char(0),char(-74),char(0),char(14),char(0),char(-73),char(0), +char(14),char(0),char(-72),char(0),char(65),char(0),char(13),char(0),char(59),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0), +char(4),char(0),char(-69),char(0),char(4),char(0),char(-68),char(0),char(4),char(0),char(-67),char(0),char(7),char(0),char(-66),char(0),char(7),char(0),char(-65),char(0), +char(7),char(0),char(-64),char(0),char(7),char(0),char(-63),char(0),char(7),char(0),char(-62),char(0),char(7),char(0),char(-61),char(0),char(7),char(0),char(-60),char(0), +char(66),char(0),char(13),char(0),char(59),char(0),char(-74),char(0),char(19),char(0),char(-71),char(0),char(19),char(0),char(-70),char(0),char(4),char(0),char(-69),char(0), +char(4),char(0),char(-68),char(0),char(4),char(0),char(-67),char(0),char(7),char(0),char(-66),char(0),char(7),char(0),char(-65),char(0),char(7),char(0),char(-64),char(0), +char(7),char(0),char(-63),char(0),char(7),char(0),char(-62),char(0),char(7),char(0),char(-61),char(0),char(7),char(0),char(-60),char(0),char(67),char(0),char(14),char(0), +char(61),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),char(4),char(0),char(-69),char(0),char(4),char(0),char(-68),char(0), +char(4),char(0),char(-67),char(0),char(8),char(0),char(-66),char(0),char(8),char(0),char(-65),char(0),char(8),char(0),char(-64),char(0),char(8),char(0),char(-63),char(0), +char(8),char(0),char(-62),char(0),char(8),char(0),char(-61),char(0),char(8),char(0),char(-60),char(0),char(0),char(0),char(-59),char(0),char(68),char(0),char(10),char(0), +char(61),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),char(8),char(0),char(-58),char(0),char(8),char(0),char(-57),char(0), +char(8),char(0),char(-56),char(0),char(8),char(0),char(-62),char(0),char(8),char(0),char(-61),char(0),char(8),char(0),char(-60),char(0),char(8),char(0),char(127),char(0), +char(69),char(0),char(11),char(0),char(59),char(0),char(-74),char(0),char(19),char(0),char(-71),char(0),char(19),char(0),char(-70),char(0),char(7),char(0),char(-58),char(0), +char(7),char(0),char(-57),char(0),char(7),char(0),char(-56),char(0),char(7),char(0),char(-62),char(0),char(7),char(0),char(-61),char(0),char(7),char(0),char(-60),char(0), +char(7),char(0),char(127),char(0),char(0),char(0),char(21),char(0),char(70),char(0),char(9),char(0),char(59),char(0),char(-74),char(0),char(19),char(0),char(-71),char(0), +char(19),char(0),char(-70),char(0),char(13),char(0),char(-55),char(0),char(13),char(0),char(-54),char(0),char(13),char(0),char(-53),char(0),char(13),char(0),char(-52),char(0), +char(4),char(0),char(-51),char(0),char(4),char(0),char(-50),char(0),char(71),char(0),char(9),char(0),char(61),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0), +char(20),char(0),char(-70),char(0),char(14),char(0),char(-55),char(0),char(14),char(0),char(-54),char(0),char(14),char(0),char(-53),char(0),char(14),char(0),char(-52),char(0), +char(4),char(0),char(-51),char(0),char(4),char(0),char(-50),char(0),char(72),char(0),char(5),char(0),char(70),char(0),char(-49),char(0),char(4),char(0),char(-48),char(0), +char(7),char(0),char(-47),char(0),char(7),char(0),char(-46),char(0),char(7),char(0),char(-45),char(0),char(73),char(0),char(5),char(0),char(71),char(0),char(-49),char(0), +char(4),char(0),char(-48),char(0),char(8),char(0),char(-47),char(0),char(8),char(0),char(-46),char(0),char(8),char(0),char(-45),char(0),char(74),char(0),char(41),char(0), +char(59),char(0),char(-74),char(0),char(19),char(0),char(-71),char(0),char(19),char(0),char(-70),char(0),char(13),char(0),char(-55),char(0),char(13),char(0),char(-54),char(0), +char(13),char(0),char(-44),char(0),char(13),char(0),char(-43),char(0),char(13),char(0),char(-42),char(0),char(13),char(0),char(-41),char(0),char(13),char(0),char(-40),char(0), +char(13),char(0),char(-39),char(0),char(13),char(0),char(-38),char(0),char(13),char(0),char(-37),char(0),char(13),char(0),char(-36),char(0),char(13),char(0),char(-35),char(0), +char(13),char(0),char(-34),char(0),char(0),char(0),char(-33),char(0),char(0),char(0),char(-32),char(0),char(0),char(0),char(-31),char(0),char(0),char(0),char(-30),char(0), +char(0),char(0),char(-29),char(0),char(0),char(0),char(-59),char(0),char(13),char(0),char(-53),char(0),char(13),char(0),char(-52),char(0),char(13),char(0),char(-28),char(0), +char(13),char(0),char(-27),char(0),char(13),char(0),char(-26),char(0),char(13),char(0),char(-25),char(0),char(13),char(0),char(-24),char(0),char(13),char(0),char(-23),char(0), +char(13),char(0),char(-22),char(0),char(13),char(0),char(-21),char(0),char(13),char(0),char(-20),char(0),char(13),char(0),char(-19),char(0),char(13),char(0),char(-18),char(0), +char(0),char(0),char(-17),char(0),char(0),char(0),char(-16),char(0),char(0),char(0),char(-15),char(0),char(0),char(0),char(-14),char(0),char(0),char(0),char(-13),char(0), +char(4),char(0),char(-12),char(0),char(75),char(0),char(41),char(0),char(61),char(0),char(-74),char(0),char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0), +char(14),char(0),char(-55),char(0),char(14),char(0),char(-54),char(0),char(14),char(0),char(-44),char(0),char(14),char(0),char(-43),char(0),char(14),char(0),char(-42),char(0), +char(14),char(0),char(-41),char(0),char(14),char(0),char(-40),char(0),char(14),char(0),char(-39),char(0),char(14),char(0),char(-38),char(0),char(14),char(0),char(-37),char(0), +char(14),char(0),char(-36),char(0),char(14),char(0),char(-35),char(0),char(14),char(0),char(-34),char(0),char(0),char(0),char(-33),char(0),char(0),char(0),char(-32),char(0), +char(0),char(0),char(-31),char(0),char(0),char(0),char(-30),char(0),char(0),char(0),char(-29),char(0),char(0),char(0),char(-59),char(0),char(14),char(0),char(-53),char(0), +char(14),char(0),char(-52),char(0),char(14),char(0),char(-28),char(0),char(14),char(0),char(-27),char(0),char(14),char(0),char(-26),char(0),char(14),char(0),char(-25),char(0), +char(14),char(0),char(-24),char(0),char(14),char(0),char(-23),char(0),char(14),char(0),char(-22),char(0),char(14),char(0),char(-21),char(0),char(14),char(0),char(-20),char(0), +char(14),char(0),char(-19),char(0),char(14),char(0),char(-18),char(0),char(0),char(0),char(-17),char(0),char(0),char(0),char(-16),char(0),char(0),char(0),char(-15),char(0), +char(0),char(0),char(-14),char(0),char(0),char(0),char(-13),char(0),char(4),char(0),char(-12),char(0),char(76),char(0),char(9),char(0),char(59),char(0),char(-74),char(0), +char(19),char(0),char(-71),char(0),char(19),char(0),char(-70),char(0),char(7),char(0),char(-55),char(0),char(7),char(0),char(-54),char(0),char(7),char(0),char(-53),char(0), +char(7),char(0),char(-52),char(0),char(4),char(0),char(-51),char(0),char(4),char(0),char(-50),char(0),char(77),char(0),char(9),char(0),char(61),char(0),char(-74),char(0), +char(20),char(0),char(-71),char(0),char(20),char(0),char(-70),char(0),char(8),char(0),char(-55),char(0),char(8),char(0),char(-54),char(0),char(8),char(0),char(-53),char(0), +char(8),char(0),char(-52),char(0),char(4),char(0),char(-51),char(0),char(4),char(0),char(-50),char(0),char(78),char(0),char(5),char(0),char(58),char(0),char(-74),char(0), +char(13),char(0),char(-11),char(0),char(13),char(0),char(-10),char(0),char(7),char(0),char(-9),char(0),char(0),char(0),char(37),char(0),char(79),char(0),char(4),char(0), +char(61),char(0),char(-74),char(0),char(14),char(0),char(-11),char(0),char(14),char(0),char(-10),char(0),char(8),char(0),char(-9),char(0),char(80),char(0),char(4),char(0), +char(7),char(0),char(-8),char(0),char(7),char(0),char(-7),char(0),char(7),char(0),char(-6),char(0),char(4),char(0),char(79),char(0),char(81),char(0),char(10),char(0), +char(80),char(0),char(-5),char(0),char(13),char(0),char(-4),char(0),char(13),char(0),char(-3),char(0),char(13),char(0),char(-2),char(0),char(13),char(0),char(-1),char(0), +char(13),char(0),char(0),char(1),char(7),char(0),char(-99),char(0),char(7),char(0),char(1),char(1),char(4),char(0),char(2),char(1),char(4),char(0),char(53),char(0), +char(82),char(0),char(4),char(0),char(80),char(0),char(-5),char(0),char(4),char(0),char(3),char(1),char(7),char(0),char(4),char(1),char(4),char(0),char(5),char(1), +char(83),char(0),char(4),char(0),char(13),char(0),char(0),char(1),char(80),char(0),char(-5),char(0),char(4),char(0),char(6),char(1),char(7),char(0),char(7),char(1), +char(84),char(0),char(7),char(0),char(13),char(0),char(8),char(1),char(80),char(0),char(-5),char(0),char(4),char(0),char(9),char(1),char(7),char(0),char(10),char(1), +char(7),char(0),char(11),char(1),char(7),char(0),char(12),char(1),char(4),char(0),char(53),char(0),char(85),char(0),char(6),char(0),char(17),char(0),char(13),char(1), +char(13),char(0),char(11),char(1),char(13),char(0),char(14),char(1),char(60),char(0),char(15),char(1),char(4),char(0),char(16),char(1),char(7),char(0),char(12),char(1), +char(86),char(0),char(26),char(0),char(4),char(0),char(17),char(1),char(7),char(0),char(18),char(1),char(7),char(0),char(127),char(0),char(7),char(0),char(19),char(1), +char(7),char(0),char(20),char(1),char(7),char(0),char(21),char(1),char(7),char(0),char(22),char(1),char(7),char(0),char(23),char(1),char(7),char(0),char(24),char(1), +char(7),char(0),char(25),char(1),char(7),char(0),char(26),char(1),char(7),char(0),char(27),char(1),char(7),char(0),char(28),char(1),char(7),char(0),char(29),char(1), +char(7),char(0),char(30),char(1),char(7),char(0),char(31),char(1),char(7),char(0),char(32),char(1),char(7),char(0),char(33),char(1),char(7),char(0),char(34),char(1), +char(7),char(0),char(35),char(1),char(7),char(0),char(36),char(1),char(4),char(0),char(37),char(1),char(4),char(0),char(38),char(1),char(4),char(0),char(39),char(1), +char(4),char(0),char(40),char(1),char(4),char(0),char(120),char(0),char(87),char(0),char(12),char(0),char(17),char(0),char(41),char(1),char(17),char(0),char(42),char(1), +char(17),char(0),char(43),char(1),char(13),char(0),char(44),char(1),char(13),char(0),char(45),char(1),char(7),char(0),char(46),char(1),char(4),char(0),char(47),char(1), +char(4),char(0),char(48),char(1),char(4),char(0),char(49),char(1),char(4),char(0),char(50),char(1),char(7),char(0),char(10),char(1),char(4),char(0),char(53),char(0), +char(88),char(0),char(27),char(0),char(19),char(0),char(51),char(1),char(17),char(0),char(52),char(1),char(17),char(0),char(53),char(1),char(13),char(0),char(44),char(1), +char(13),char(0),char(54),char(1),char(13),char(0),char(55),char(1),char(13),char(0),char(56),char(1),char(13),char(0),char(57),char(1),char(13),char(0),char(58),char(1), +char(4),char(0),char(59),char(1),char(7),char(0),char(60),char(1),char(4),char(0),char(61),char(1),char(4),char(0),char(62),char(1),char(4),char(0),char(63),char(1), +char(7),char(0),char(64),char(1),char(7),char(0),char(65),char(1),char(4),char(0),char(66),char(1),char(4),char(0),char(67),char(1),char(7),char(0),char(68),char(1), +char(7),char(0),char(69),char(1),char(7),char(0),char(70),char(1),char(7),char(0),char(71),char(1),char(7),char(0),char(72),char(1),char(7),char(0),char(73),char(1), +char(4),char(0),char(74),char(1),char(4),char(0),char(75),char(1),char(4),char(0),char(76),char(1),char(89),char(0),char(12),char(0),char(9),char(0),char(77),char(1), +char(9),char(0),char(78),char(1),char(13),char(0),char(79),char(1),char(7),char(0),char(80),char(1),char(7),char(0),char(-125),char(0),char(7),char(0),char(81),char(1), +char(4),char(0),char(82),char(1),char(13),char(0),char(83),char(1),char(4),char(0),char(84),char(1),char(4),char(0),char(85),char(1),char(4),char(0),char(86),char(1), +char(4),char(0),char(53),char(0),char(90),char(0),char(19),char(0),char(50),char(0),char(-109),char(0),char(87),char(0),char(87),char(1),char(80),char(0),char(88),char(1), +char(81),char(0),char(89),char(1),char(82),char(0),char(90),char(1),char(83),char(0),char(91),char(1),char(84),char(0),char(92),char(1),char(85),char(0),char(93),char(1), +char(88),char(0),char(94),char(1),char(89),char(0),char(95),char(1),char(4),char(0),char(96),char(1),char(4),char(0),char(62),char(1),char(4),char(0),char(97),char(1), +char(4),char(0),char(98),char(1),char(4),char(0),char(99),char(1),char(4),char(0),char(100),char(1),char(4),char(0),char(101),char(1),char(4),char(0),char(102),char(1), +char(86),char(0),char(103),char(1),char(91),char(0),char(24),char(0),char(16),char(0),char(104),char(1),char(14),char(0),char(105),char(1),char(14),char(0),char(106),char(1), +char(14),char(0),char(107),char(1),char(14),char(0),char(108),char(1),char(14),char(0),char(109),char(1),char(8),char(0),char(110),char(1),char(4),char(0),char(111),char(1), +char(4),char(0),char(86),char(1),char(4),char(0),char(112),char(1),char(4),char(0),char(113),char(1),char(8),char(0),char(114),char(1),char(8),char(0),char(115),char(1), +char(8),char(0),char(116),char(1),char(8),char(0),char(117),char(1),char(8),char(0),char(118),char(1),char(8),char(0),char(119),char(1),char(8),char(0),char(120),char(1), +char(8),char(0),char(121),char(1),char(8),char(0),char(122),char(1),char(0),char(0),char(123),char(1),char(0),char(0),char(124),char(1),char(49),char(0),char(125),char(1), +char(0),char(0),char(126),char(1),char(92),char(0),char(24),char(0),char(15),char(0),char(104),char(1),char(13),char(0),char(105),char(1),char(13),char(0),char(106),char(1), +char(13),char(0),char(107),char(1),char(13),char(0),char(108),char(1),char(13),char(0),char(109),char(1),char(4),char(0),char(112),char(1),char(7),char(0),char(110),char(1), +char(4),char(0),char(111),char(1),char(4),char(0),char(86),char(1),char(7),char(0),char(114),char(1),char(7),char(0),char(115),char(1),char(7),char(0),char(116),char(1), +char(4),char(0),char(113),char(1),char(7),char(0),char(117),char(1),char(7),char(0),char(118),char(1),char(7),char(0),char(119),char(1),char(7),char(0),char(120),char(1), +char(7),char(0),char(121),char(1),char(7),char(0),char(122),char(1),char(0),char(0),char(123),char(1),char(0),char(0),char(124),char(1),char(50),char(0),char(125),char(1), +char(0),char(0),char(126),char(1),char(93),char(0),char(9),char(0),char(20),char(0),char(127),char(1),char(14),char(0),char(-128),char(1),char(8),char(0),char(-127),char(1), +char(0),char(0),char(-126),char(1),char(91),char(0),char(90),char(1),char(49),char(0),char(-125),char(1),char(0),char(0),char(126),char(1),char(4),char(0),char(97),char(1), +char(0),char(0),char(37),char(0),char(94),char(0),char(7),char(0),char(0),char(0),char(-126),char(1),char(92),char(0),char(90),char(1),char(50),char(0),char(-125),char(1), +char(19),char(0),char(127),char(1),char(13),char(0),char(-128),char(1),char(7),char(0),char(-127),char(1),char(4),char(0),char(97),char(1),}; int sBulletDNAlen64= sizeof(sBulletDNAstr64); diff --git a/extern/bullet/src/LinearMath/btThreads.cpp b/extern/bullet/src/LinearMath/btThreads.cpp index c037626ffb0e..59a7ea36e9ac 100644 --- a/extern/bullet/src/LinearMath/btThreads.cpp +++ b/extern/bullet/src/LinearMath/btThreads.cpp @@ -453,33 +453,6 @@ void btParallelFor( int iBegin, int iEnd, int grainSize, const btIParallelForBod #endif// #if BT_THREADSAFE } -btScalar btParallelSum( int iBegin, int iEnd, int grainSize, const btIParallelSumBody& body ) -{ -#if BT_THREADSAFE - -#if BT_DETECT_BAD_THREAD_INDEX - if ( !btThreadsAreRunning() ) - { - // clear out thread ids - for ( int i = 0; i < BT_MAX_THREAD_COUNT; ++i ) - { - gDebugThreadIds[ i ] = kInvalidThreadId; - } - } -#endif // #if BT_DETECT_BAD_THREAD_INDEX - - btAssert( gBtTaskScheduler != NULL ); // call btSetTaskScheduler() with a valid task scheduler first! - return gBtTaskScheduler->parallelSum( iBegin, iEnd, grainSize, body ); - -#else // #if BT_THREADSAFE - - // non-parallel version of btParallelSum - btAssert( !"called btParallelFor in non-threadsafe build. enable BT_THREADSAFE" ); - return body.sumLoop( iBegin, iEnd ); - -#endif //#else // #if BT_THREADSAFE -} - /// /// btTaskSchedulerSequential -- non-threaded implementation of task scheduler @@ -497,11 +470,6 @@ class btTaskSchedulerSequential : public btITaskScheduler BT_PROFILE( "parallelFor_sequential" ); body.forLoop( iBegin, iEnd ); } - virtual btScalar parallelSum( int iBegin, int iEnd, int grainSize, const btIParallelSumBody& body ) BT_OVERRIDE - { - BT_PROFILE( "parallelSum_sequential" ); - return body.sumLoop( iBegin, iEnd ); - } }; @@ -546,25 +514,11 @@ class btTaskSchedulerOpenMP : public btITaskScheduler #pragma omp parallel for schedule( static, 1 ) for ( int i = iBegin; i < iEnd; i += grainSize ) { - BT_PROFILE( "OpenMP_forJob" ); + BT_PROFILE( "OpenMP_job" ); body.forLoop( i, ( std::min )( i + grainSize, iEnd ) ); } btPopThreadsAreRunning(); } - virtual btScalar parallelSum( int iBegin, int iEnd, int grainSize, const btIParallelSumBody& body ) BT_OVERRIDE - { - BT_PROFILE( "parallelFor_OpenMP" ); - btPushThreadsAreRunning(); - btScalar sum = btScalar( 0 ); -#pragma omp parallel for schedule( static, 1 ) reduction(+:sum) - for ( int i = iBegin; i < iEnd; i += grainSize ) - { - BT_PROFILE( "OpenMP_sumJob" ); - sum += body.sumLoop( i, ( std::min )( i + grainSize, iEnd ) ); - } - btPopThreadsAreRunning(); - return sum; - } }; #endif // #if BT_USE_OPENMP && BT_THREADSAFE @@ -617,21 +571,22 @@ class btTaskSchedulerTBB : public btITaskScheduler btResetThreadIndexCounter(); } } - struct ForBodyAdapter + struct BodyAdapter { const btIParallelForBody* mBody; - ForBodyAdapter( const btIParallelForBody* body ) : mBody( body ) {} void operator()( const tbb::blocked_range& range ) const { - BT_PROFILE( "TBB_forJob" ); + BT_PROFILE( "TBB_job" ); mBody->forLoop( range.begin(), range.end() ); } }; virtual void parallelFor( int iBegin, int iEnd, int grainSize, const btIParallelForBody& body ) BT_OVERRIDE { BT_PROFILE( "parallelFor_TBB" ); - ForBodyAdapter tbbBody( &body ); + // TBB dispatch + BodyAdapter tbbBody; + tbbBody.mBody = &body; btPushThreadsAreRunning(); tbb::parallel_for( tbb::blocked_range( iBegin, iEnd, grainSize ), tbbBody, @@ -639,29 +594,6 @@ class btTaskSchedulerTBB : public btITaskScheduler ); btPopThreadsAreRunning(); } - struct SumBodyAdapter - { - const btIParallelSumBody* mBody; - btScalar mSum; - - SumBodyAdapter( const btIParallelSumBody* body ) : mBody( body ), mSum( btScalar( 0 ) ) {} - SumBodyAdapter( const SumBodyAdapter& src, tbb::split ) : mBody( src.mBody ), mSum( btScalar( 0 ) ) {} - void join( const SumBodyAdapter& src ) { mSum += src.mSum; } - void operator()( const tbb::blocked_range& range ) - { - BT_PROFILE( "TBB_sumJob" ); - mSum += mBody->sumLoop( range.begin(), range.end() ); - } - }; - virtual btScalar parallelSum( int iBegin, int iEnd, int grainSize, const btIParallelSumBody& body ) BT_OVERRIDE - { - BT_PROFILE( "parallelSum_TBB" ); - SumBodyAdapter tbbBody( &body ); - btPushThreadsAreRunning(); - tbb::parallel_deterministic_reduce( tbb::blocked_range( iBegin, iEnd, grainSize ), tbbBody ); - btPopThreadsAreRunning(); - return tbbBody.mSum; - } }; #endif // #if BT_USE_TBB && BT_THREADSAFE @@ -673,7 +605,6 @@ class btTaskSchedulerTBB : public btITaskScheduler class btTaskSchedulerPPL : public btITaskScheduler { int m_numThreads; - concurrency::combinable m_sum; // for parallelSum public: btTaskSchedulerPPL() : btITaskScheduler( "PPL" ) { @@ -713,16 +644,15 @@ class btTaskSchedulerPPL : public btITaskScheduler btResetThreadIndexCounter(); } } - struct ForBodyAdapter + struct BodyAdapter { const btIParallelForBody* mBody; int mGrainSize; int mIndexEnd; - ForBodyAdapter( const btIParallelForBody* body, int grainSize, int end ) : mBody( body ), mGrainSize( grainSize ), mIndexEnd( end ) {} void operator()( int i ) const { - BT_PROFILE( "PPL_forJob" ); + BT_PROFILE( "PPL_job" ); mBody->forLoop( i, ( std::min )( i + mGrainSize, mIndexEnd ) ); } }; @@ -730,36 +660,10 @@ class btTaskSchedulerPPL : public btITaskScheduler { BT_PROFILE( "parallelFor_PPL" ); // PPL dispatch - ForBodyAdapter pplBody( &body, grainSize, iEnd ); - btPushThreadsAreRunning(); - // note: MSVC 2010 doesn't support partitioner args, so avoid them - concurrency::parallel_for( iBegin, - iEnd, - grainSize, - pplBody - ); - btPopThreadsAreRunning(); - } - struct SumBodyAdapter - { - const btIParallelSumBody* mBody; - concurrency::combinable* mSum; - int mGrainSize; - int mIndexEnd; - - SumBodyAdapter( const btIParallelSumBody* body, concurrency::combinable* sum, int grainSize, int end ) : mBody( body ), mSum(sum), mGrainSize( grainSize ), mIndexEnd( end ) {} - void operator()( int i ) const - { - BT_PROFILE( "PPL_sumJob" ); - mSum->local() += mBody->sumLoop( i, ( std::min )( i + mGrainSize, mIndexEnd ) ); - } - }; - static btScalar sumFunc( btScalar a, btScalar b ) { return a + b; } - virtual btScalar parallelSum( int iBegin, int iEnd, int grainSize, const btIParallelSumBody& body ) BT_OVERRIDE - { - BT_PROFILE( "parallelSum_PPL" ); - m_sum.clear(); - SumBodyAdapter pplBody( &body, &m_sum, grainSize, iEnd ); + BodyAdapter pplBody; + pplBody.mBody = &body; + pplBody.mGrainSize = grainSize; + pplBody.mIndexEnd = iEnd; btPushThreadsAreRunning(); // note: MSVC 2010 doesn't support partitioner args, so avoid them concurrency::parallel_for( iBegin, @@ -768,7 +672,6 @@ class btTaskSchedulerPPL : public btITaskScheduler pplBody ); btPopThreadsAreRunning(); - return m_sum.combine( sumFunc ); } }; #endif // #if BT_USE_PPL && BT_THREADSAFE diff --git a/extern/bullet/src/LinearMath/btThreads.h b/extern/bullet/src/LinearMath/btThreads.h index 921fd088c0b4..05fd15ec82ef 100644 --- a/extern/bullet/src/LinearMath/btThreads.h +++ b/extern/bullet/src/LinearMath/btThreads.h @@ -28,8 +28,6 @@ subject to the following restrictions: #define BT_OVERRIDE #endif -// Don't set this to larger than 64, without modifying btThreadSupportPosix -// and btThreadSupportWin32. They use UINT64 bit-masks. const unsigned int BT_MAX_THREAD_COUNT = 64; // only if BT_THREADSAFE is 1 // for internal use only @@ -74,8 +72,6 @@ SIMD_FORCE_INLINE void btMutexLock( btSpinMutex* mutex ) { #if BT_THREADSAFE mutex->lock(); -#else - (void)mutex; #endif // #if BT_THREADSAFE } @@ -83,8 +79,6 @@ SIMD_FORCE_INLINE void btMutexUnlock( btSpinMutex* mutex ) { #if BT_THREADSAFE mutex->unlock(); -#else - (void)mutex; #endif // #if BT_THREADSAFE } @@ -93,7 +87,6 @@ SIMD_FORCE_INLINE bool btMutexTryLock( btSpinMutex* mutex ) #if BT_THREADSAFE return mutex->tryLock(); #else - (void)mutex; return true; #endif // #if BT_THREADSAFE } @@ -109,17 +102,6 @@ class btIParallelForBody virtual void forLoop( int iBegin, int iEnd ) const = 0; }; -// -// btIParallelSumBody -- subclass this to express work that can be done in parallel -// and produces a sum over all loop elements -// -class btIParallelSumBody -{ -public: - virtual ~btIParallelSumBody() {} - virtual btScalar sumLoop( int iBegin, int iEnd ) const = 0; -}; - // // btITaskScheduler -- subclass this to implement a task scheduler that can dispatch work to // worker threads @@ -135,8 +117,6 @@ class btITaskScheduler virtual int getNumThreads() const = 0; virtual void setNumThreads( int numThreads ) = 0; virtual void parallelFor( int iBegin, int iEnd, int grainSize, const btIParallelForBody& body ) = 0; - virtual btScalar parallelSum( int iBegin, int iEnd, int grainSize, const btIParallelSumBody& body ) = 0; - virtual void sleepWorkerThreadsHint() {} // hint the task scheduler that we may not be using these threads for a little while // internal use only virtual void activate(); @@ -158,9 +138,6 @@ btITaskScheduler* btGetTaskScheduler(); // get non-threaded task scheduler (always available) btITaskScheduler* btGetSequentialTaskScheduler(); -// create a default task scheduler (Win32 or pthreads based) -btITaskScheduler* btCreateDefaultTaskScheduler(); - // get OpenMP task scheduler (if available, otherwise returns null) btITaskScheduler* btGetOpenMPTaskScheduler(); @@ -174,9 +151,5 @@ btITaskScheduler* btGetPPLTaskScheduler(); // (iterations may be done out of order, so no dependencies are allowed) void btParallelFor( int iBegin, int iEnd, int grainSize, const btIParallelForBody& body ); -// btParallelSum -- call this to dispatch work like a for-loop, returns the sum of all iterations -// (iterations may be done out of order, so no dependencies are allowed) -btScalar btParallelSum( int iBegin, int iEnd, int grainSize, const btIParallelSumBody& body ); - #endif diff --git a/extern/bullet/src/LinearMath/btVector3.cpp b/extern/bullet/src/LinearMath/btVector3.cpp index e05bdccd67e2..dbcf2b6ab57e 100644 --- a/extern/bullet/src/LinearMath/btVector3.cpp +++ b/extern/bullet/src/LinearMath/btVector3.cpp @@ -15,9 +15,9 @@ This source version has been altered. */ -#if defined (_WIN32) || defined (__i386__) -#define BT_USE_SSE_IN_API -#endif +//#if defined (_WIN32) || defined (__i386__) +//#define BT_USE_SSE_IN_API +//#endif #include "btVector3.h" diff --git a/extern/bullet/src/LinearMath/btVector3.h b/extern/bullet/src/LinearMath/btVector3.h index cfc9354ecee1..fdf3fd796fc3 100644 --- a/extern/bullet/src/LinearMath/btVector3.h +++ b/extern/bullet/src/LinearMath/btVector3.h @@ -368,7 +368,7 @@ ATTRIBUTE_ALIGNED16(class) btVector3 return btAcos(dot(v) / s); } - /**@brief Return a vector with the absolute values of each element */ + /**@brief Return a vector will the absolute values of each element */ SIMD_FORCE_INLINE btVector3 absolute() const { @@ -705,9 +705,7 @@ ATTRIBUTE_ALIGNED16(class) btVector3 SIMD_FORCE_INLINE void serialize(struct btVector3Data& dataOut) const; - SIMD_FORCE_INLINE void deSerialize(const struct btVector3DoubleData& dataIn); - - SIMD_FORCE_INLINE void deSerialize(const struct btVector3FloatData& dataIn); + SIMD_FORCE_INLINE void deSerialize(const struct btVector3Data& dataIn); SIMD_FORCE_INLINE void serializeFloat(struct btVector3FloatData& dataOut) const; @@ -1189,6 +1187,7 @@ class btVector4 : public btVector3 if (m_floats[3] < minVal) { minIndex = 3; + minVal = m_floats[3]; } return minIndex; @@ -1356,18 +1355,10 @@ SIMD_FORCE_INLINE void btVector3::serialize(struct btVector3Data& dataOut) const dataOut.m_floats[i] = m_floats[i]; } - -SIMD_FORCE_INLINE void btVector3::deSerialize(const struct btVector3FloatData& dataIn) -{ - for (int i = 0; i<4; i++) - m_floats[i] = (btScalar)dataIn.m_floats[i]; -} - - -SIMD_FORCE_INLINE void btVector3::deSerialize(const struct btVector3DoubleData& dataIn) +SIMD_FORCE_INLINE void btVector3::deSerialize(const struct btVector3Data& dataIn) { for (int i=0;i<4;i++) - m_floats[i] = (btScalar)dataIn.m_floats[i]; + m_floats[i] = dataIn.m_floats[i]; } #endif //BT_VECTOR3_H diff --git a/extern/bullet/src/LinearMath/premake4.lua b/extern/bullet/src/LinearMath/premake4.lua index 3765811a943e..524e2c316160 100644 --- a/extern/bullet/src/LinearMath/premake4.lua +++ b/extern/bullet/src/LinearMath/premake4.lua @@ -1,15 +1,10 @@ project "LinearMath" kind "StaticLib" - if os.is("Linux") then - buildoptions{"-fPIC"} - end includedirs { "..", } files { "*.cpp", - "*.h", - "TaskScheduler/*.cpp", - "TaskScheduler/*.h" + "*.h" } diff --git a/extern/bullet/src/clew/clew.c b/extern/bullet/src/clew/clew.c index 5afc42a48553..a07b0aad754f 100644 --- a/extern/bullet/src/clew/clew.c +++ b/extern/bullet/src/clew/clew.c @@ -15,7 +15,7 @@ typedef HMODULE CLEW_DYNLIB_HANDLE; - #define CLEW_DYNLIB_OPEN LoadLibraryA + #define CLEW_DYNLIB_OPEN LoadLibrary #define CLEW_DYNLIB_CLOSE FreeLibrary #define CLEW_DYNLIB_IMPORT GetProcAddress #else diff --git a/source/gameengine/Physics/Bullet/CcdPhysicsEnvironment.cpp b/source/gameengine/Physics/Bullet/CcdPhysicsEnvironment.cpp index 94fe7b30f4aa..f291f252e96d 100644 --- a/source/gameengine/Physics/Bullet/CcdPhysicsEnvironment.cpp +++ b/source/gameengine/Physics/Bullet/CcdPhysicsEnvironment.cpp @@ -32,7 +32,6 @@ #include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h" #include "BulletCollision/Gimpact/btGImpactCollisionAlgorithm.h" #include "BulletCollision/NarrowPhaseCollision/btRaycastCallback.h" -#include "BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.h" #include "BulletDynamics/ConstraintSolver/btNNCGConstraintSolver.h" #include "BulletDynamics/MLCPSolvers/btMLCPSolver.h" #include "BulletDynamics/MLCPSolvers/btDantzigSolver.h" @@ -423,7 +422,6 @@ CcdPhysicsEnvironment::CcdPhysicsEnvironment(PHY_SolverType solverType, bool use m_broadphase(new btDbvtBroadphase()), m_cullingCache(nullptr), m_cullingTree(nullptr), - m_solverMt(new btSequentialImpulseConstraintSolverMt()), m_filterCallback(new CcdOverlapFilterCallBack(this)), m_ghostPairCallback(new btGhostPairCallback()), m_dispatcher(new btCollisionDispatcherMt(m_collisionConfiguration.get())), @@ -463,7 +461,7 @@ CcdPhysicsEnvironment::CcdPhysicsEnvironment(PHY_SolverType solverType, bool use SetSolverType(solverType); m_solverPool.reset(new btConstraintSolverPoolMt(m_solvers.data(), numThread)); - m_dynamicsWorld.reset(new btSoftRigidDynamicsWorldMt(m_dispatcher.get(), m_broadphase.get(), m_solverPool.get(), m_solverMt.get(), m_collisionConfiguration.get())); + m_dynamicsWorld.reset(new btSoftRigidDynamicsWorldMt(m_dispatcher.get(), m_broadphase.get(), m_solverPool.get(), m_collisionConfiguration.get())); m_dynamicsWorld->setInternalTickCallback(&CcdPhysicsEnvironment::StaticSimulationSubtickCallback, this); m_dynamicsWorld->setDebugDrawer(&m_debugDrawer); diff --git a/source/gameengine/Physics/Bullet/CcdPhysicsEnvironment.h b/source/gameengine/Physics/Bullet/CcdPhysicsEnvironment.h index 709bf36ee687..66084d156093 100644 --- a/source/gameengine/Physics/Bullet/CcdPhysicsEnvironment.h +++ b/source/gameengine/Physics/Bullet/CcdPhysicsEnvironment.h @@ -116,7 +116,6 @@ class CcdPhysicsEnvironment : public PHY_IPhysicsEnvironment, public mt::SimdCla std::unique_ptr m_solverPool; std::vector m_solvers; - std::unique_ptr m_solverMt; std::unique_ptr m_filterCallback;