From 9a7e30d09ffe20a533ad76b1729e66232aa5de89 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Thu, 8 Aug 2019 15:00:55 -0700 Subject: move deformable examples to a single folder and rename them; change license to google 2016 --- examples/CMakeLists.txt | 2 +- examples/DeformableContact/DeformableContact.cpp | 411 --------------------- examples/DeformableContact/DeformableContact.h | 20 - examples/DeformableDemo/DeformableDemo.cpp | 293 --------------- examples/DeformableDemo/DeformableDemo.h | 20 - examples/DeformableDemo/DeformableMultibody.cpp | 409 ++++++++++++++++++++ examples/DeformableDemo/DeformableMultibody.h | 19 + examples/DeformableDemo/DeformableRigid.cpp | 291 +++++++++++++++ examples/DeformableDemo/DeformableRigid.h | 19 + examples/DeformableDemo/Pinch.cpp | 397 ++++++++++++++++++++ examples/DeformableDemo/Pinch.h | 19 + examples/DeformableDemo/VolumetricDeformable.cpp | 296 +++++++++++++++ examples/DeformableDemo/VolumetricDeformable.h | 19 + examples/ExampleBrowser/CMakeLists.txt | 16 +- examples/ExampleBrowser/ExampleEntries.cpp | 13 +- examples/ExampleBrowser/premake4.lua | 3 - examples/Pinch/Pinch.cpp | 399 -------------------- examples/Pinch/Pinch.h | 20 - .../VolumetricDeformable/VolumetricDeformable.cpp | 298 --------------- .../VolumetricDeformable/VolumetricDeformable.h | 20 - .../btDeformableRigidDynamicsWorld.h | 4 +- 21 files changed, 1485 insertions(+), 1503 deletions(-) delete mode 100644 examples/DeformableContact/DeformableContact.cpp delete mode 100644 examples/DeformableContact/DeformableContact.h delete mode 100644 examples/DeformableDemo/DeformableDemo.cpp delete mode 100644 examples/DeformableDemo/DeformableDemo.h create mode 100644 examples/DeformableDemo/DeformableMultibody.cpp create mode 100644 examples/DeformableDemo/DeformableMultibody.h create mode 100644 examples/DeformableDemo/DeformableRigid.cpp create mode 100644 examples/DeformableDemo/DeformableRigid.h create mode 100644 examples/DeformableDemo/Pinch.cpp create mode 100644 examples/DeformableDemo/Pinch.h create mode 100644 examples/DeformableDemo/VolumetricDeformable.cpp create mode 100644 examples/DeformableDemo/VolumetricDeformable.h delete mode 100644 examples/Pinch/Pinch.cpp delete mode 100644 examples/Pinch/Pinch.h delete mode 100644 examples/VolumetricDeformable/VolumetricDeformable.cpp delete mode 100644 examples/VolumetricDeformable/VolumetricDeformable.h diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 1918a9003..ba9efac19 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -1,4 +1,4 @@ -SUBDIRS( HelloWorld BasicDemo ) +SUBDIRS( HelloWorld BasicDemo) IF(BUILD_BULLET3) SUBDIRS( ExampleBrowser RobotSimulator SharedMemory ThirdPartyLibs/Gwen ThirdPartyLibs/BussIK ThirdPartyLibs/clsocket OpenGLWindow TwoJoint ) ENDIF() diff --git a/examples/DeformableContact/DeformableContact.cpp b/examples/DeformableContact/DeformableContact.cpp deleted file mode 100644 index 102ad40a9..000000000 --- a/examples/DeformableContact/DeformableContact.cpp +++ /dev/null @@ -1,411 +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. -*/ - -///create 125 (5x5x5) dynamic object -#define ARRAY_SIZE_X 5 -#define ARRAY_SIZE_Y 5 -#define ARRAY_SIZE_Z 5 - -//maximum number of objects (and allow user to shoot additional boxes) -#define MAX_PROXIES (ARRAY_SIZE_X * ARRAY_SIZE_Y * ARRAY_SIZE_Z + 1024) - -///scaling of the objects (0.1 = 20 centimeter boxes ) -#define SCALING 1. -#define START_POS_X -5 -#define START_POS_Y -5 -#define START_POS_Z -3 - -#include "DeformableContact.h" -///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files. -#include "btBulletDynamicsCommon.h" -#include "BulletSoftBody/btDeformableRigidDynamicsWorld.h" -#include "BulletSoftBody/btSoftBody.h" -#include "BulletSoftBody/btSoftBodyHelpers.h" -#include "BulletSoftBody/btDeformableBodySolver.h" -#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h" -#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" -#include //printf debugging - -#include "../CommonInterfaces/CommonRigidBodyBase.h" -#include "../Utils/b3ResourcePath.h" -#include "../SoftDemo/BunnyMesh.h" -#include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h" -#include "BulletDynamics/Featherstone/btMultiBodyJointFeedback.h" - -#include "../CommonInterfaces/CommonMultiBodyBase.h" -#include "../Utils/b3ResourcePath.h" -///The DeformableContact demo deformable bodies self-collision -static bool g_floatingBase = true; -static float friction = 1.; -class DeformableContact : public CommonMultiBodyBase -{ - btMultiBody* m_multiBody; - btAlignedObjectArray m_jointFeedbacks; -public: - DeformableContact(struct GUIHelperInterface* helper) - : CommonMultiBodyBase(helper) - { - } - - virtual ~DeformableContact() - { - } - - void initPhysics(); - - void exitPhysics(); - - void resetCamera() - { - float dist = 30; - float pitch = -30; - float yaw = 100; - float targetPos[3] = {0, -10, 0}; - m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]); - } - - virtual void stepSimulation(float deltaTime); - - btMultiBody* createFeatherstoneMultiBody_testMultiDof(class btMultiBodyDynamicsWorld* world, int numLinks, const btVector3& basePosition, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents, bool spherical = false, bool floating = false); - - void addColliders_testMultiDof(btMultiBody* pMultiBody, btMultiBodyDynamicsWorld* pWorld, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents); - - - virtual const btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() const - { - return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; - } - - virtual btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() - { - return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; - } - - virtual void renderScene() - { - CommonMultiBodyBase::renderScene(); - btDeformableRigidDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); - - for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++) - { - btSoftBody* psb = (btSoftBody*)deformableWorld->getSoftBodyArray()[i]; - { - btSoftBodyHelpers::DrawFrame(psb, deformableWorld->getDebugDrawer()); - btSoftBodyHelpers::Draw(psb, deformableWorld->getDebugDrawer(), deformableWorld->getDrawFlags()); - } - } - } -}; - -void DeformableContact::initPhysics() -{ - m_guiHelper->setUpAxis(1); - - ///collision configuration contains default setup for memory, collision setup - m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration(); - - ///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(); - btDeformableBodySolver* deformableBodySolver = new btDeformableBodySolver(); - btMultiBodyConstraintSolver* sol; - sol = new btMultiBodyConstraintSolver; - m_solver = sol; - - m_dynamicsWorld = new btDeformableRigidDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); - deformableBodySolver->setWorld(getDeformableDynamicsWorld()); - btVector3 gravity = btVector3(0, -10, 0); - m_dynamicsWorld->setGravity(gravity); - getDeformableDynamicsWorld()->getWorldInfo().m_gravity = gravity; - m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); - - { - ///create a ground - btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(150.), btScalar(25.), btScalar(150.))); - - m_collisionShapes.push_back(groundShape); - - btTransform groundTransform; - groundTransform.setIdentity(); - groundTransform.setOrigin(btVector3(0, -40, 0)); - groundTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0.)); - //We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here: - btScalar mass(0.); - - //rigidbody is dynamic if and only if mass is non zero, otherwise static - bool isDynamic = (mass != 0.f); - - btVector3 localInertia(0, 0, 0); - if (isDynamic) - groundShape->calculateLocalInertia(mass, localInertia); - - //using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects - btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform); - btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia); - btRigidBody* body = new btRigidBody(rbInfo); - body->setFriction(0.5); - - //add the ground to the dynamics world - m_dynamicsWorld->addRigidBody(body,1,1+2); - } - - - { - bool damping = true; - bool gyro = false; - int numLinks = 4; - bool spherical = false; //set it ot false -to use 1DoF hinges instead of 3DoF sphericals - bool canSleep = false; - bool selfCollide = true; - btVector3 linkHalfExtents(.4, 1, .4); - btVector3 baseHalfExtents(.4, 1, .4); - - btMultiBody* mbC = createFeatherstoneMultiBody_testMultiDof(m_dynamicsWorld, numLinks, btVector3(0.f, 10.f,0.f), linkHalfExtents, baseHalfExtents, spherical, g_floatingBase); - - mbC->setCanSleep(canSleep); - mbC->setHasSelfCollision(selfCollide); - mbC->setUseGyroTerm(gyro); - // - if (!damping) - { - mbC->setLinearDamping(0.0f); - mbC->setAngularDamping(0.0f); - } - else - { - mbC->setLinearDamping(0.04f); - mbC->setAngularDamping(0.04f); - } - - if (numLinks > 0) - { - btScalar q0 = 0.f * SIMD_PI / 180.f; - if (!spherical) - { - mbC->setJointPosMultiDof(0, &q0); - } - else - { - btQuaternion quat0(btVector3(1, 1, 0).normalized(), q0); - quat0.normalize(); - mbC->setJointPosMultiDof(0, quat0); - } - } - /// - addColliders_testMultiDof(mbC, m_dynamicsWorld, baseHalfExtents, linkHalfExtents); - } - - // create a patch of cloth - { - btScalar h = 0; - const btScalar s = 4; - btSoftBody* psb = btSoftBodyHelpers::CreatePatch(getDeformableDynamicsWorld()->getWorldInfo(), btVector3(-s, h, -s), - btVector3(+s, h, -s), - btVector3(-s, h, +s), - btVector3(+s, h, +s), - 20,20, -// 3,3, - 1 + 2 + 4 + 8, true); - - psb->getCollisionShape()->setMargin(0.25); - psb->generateBendingConstraints(2); - psb->setTotalMass(5); - psb->setSpringStiffness(2); - psb->setDampingCoefficient(0.01); - psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects - psb->m_cfg.kCHR = 1; // collision hardness with rigid body - psb->m_cfg.kDF = .1; - psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; - getDeformableDynamicsWorld()->addSoftBody(psb); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce()); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); - } - - m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); -} - -void DeformableContact::exitPhysics() -{ - //cleanup in the reverse order of creation/initialization - - //remove the rigidbodies from the dynamics world and delete them - int i; - for (i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--) - { - btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i]; - btRigidBody* body = btRigidBody::upcast(obj); - if (body && body->getMotionState()) - { - delete body->getMotionState(); - } - m_dynamicsWorld->removeCollisionObject(obj); - delete obj; - } - - //delete collision shapes - for (int j = 0; j < m_collisionShapes.size(); j++) - { - btCollisionShape* shape = m_collisionShapes[j]; - delete shape; - } - m_collisionShapes.clear(); - - delete m_dynamicsWorld; - - delete m_solver; - - delete m_broadphase; - - delete m_dispatcher; - - delete m_collisionConfiguration; -} - -void DeformableContact::stepSimulation(float deltaTime) -{ -// getDeformableDynamicsWorld()->getMultiBodyDynamicsWorld()->stepSimulation(deltaTime); - m_dynamicsWorld->stepSimulation(deltaTime, 5, 1./250.); -} - - -btMultiBody* DeformableContact::createFeatherstoneMultiBody_testMultiDof(btMultiBodyDynamicsWorld* pWorld, int numLinks, const btVector3& basePosition, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents, bool spherical, bool floating) -{ - //init the base - btVector3 baseInertiaDiag(0.f, 0.f, 0.f); - float baseMass = .1f; - - if (baseMass) - { - btCollisionShape* pTempBox = new btBoxShape(btVector3(baseHalfExtents[0], baseHalfExtents[1], baseHalfExtents[2])); - pTempBox->calculateLocalInertia(baseMass, baseInertiaDiag); - delete pTempBox; - } - - bool canSleep = false; - - btMultiBody* pMultiBody = new btMultiBody(numLinks, baseMass, baseInertiaDiag, !floating, canSleep); - - btQuaternion baseOriQuat(0.f, 0.f, 0.f, 1.f); - pMultiBody->setBasePos(basePosition); - pMultiBody->setWorldToBaseRot(baseOriQuat); - btVector3 vel(0, 0, 0); - // pMultiBody->setBaseVel(vel); - - //init the links - btVector3 hingeJointAxis(1, 0, 0); - float linkMass = .1f; - btVector3 linkInertiaDiag(0.f, 0.f, 0.f); - - btCollisionShape* pTempBox = new btBoxShape(btVector3(linkHalfExtents[0], linkHalfExtents[1], linkHalfExtents[2])); - pTempBox->calculateLocalInertia(linkMass, linkInertiaDiag); - delete pTempBox; - - //y-axis assumed up - btVector3 parentComToCurrentCom(0, -linkHalfExtents[1] * 2.f, 0); //par body's COM to cur body's COM offset - btVector3 currentPivotToCurrentCom(0, -linkHalfExtents[1], 0); //cur body's COM to cur body's PIV offset - btVector3 parentComToCurrentPivot = parentComToCurrentCom - currentPivotToCurrentCom; //par body's COM to cur body's PIV offset - - ////// - btScalar q0 = 0.f * SIMD_PI / 180.f; - btQuaternion quat0(btVector3(0, 1, 0).normalized(), q0); - quat0.normalize(); - ///// - - for (int i = 0; i < numLinks; ++i) - { - if (!spherical) - pMultiBody->setupRevolute(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f), hingeJointAxis, parentComToCurrentPivot, currentPivotToCurrentCom, true); - else - //pMultiBody->setupPlanar(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f)/*quat0*/, btVector3(1, 0, 0), parentComToCurrentPivot*2, false); - pMultiBody->setupSpherical(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f), parentComToCurrentPivot, currentPivotToCurrentCom, true); - } - - pMultiBody->finalizeMultiDof(); - - /// - pWorld->addMultiBody(pMultiBody); - /// - return pMultiBody; -} - -void DeformableContact::addColliders_testMultiDof(btMultiBody* pMultiBody, btMultiBodyDynamicsWorld* pWorld, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents) -{ - btAlignedObjectArray world_to_local; - world_to_local.resize(pMultiBody->getNumLinks() + 1); - - btAlignedObjectArray local_origin; - local_origin.resize(pMultiBody->getNumLinks() + 1); - world_to_local[0] = pMultiBody->getWorldToBaseRot(); - local_origin[0] = pMultiBody->getBasePos(); - - { - // float pos[4]={local_origin[0].x(),local_origin[0].y(),local_origin[0].z(),1}; - btScalar quat[4] = {-world_to_local[0].x(), -world_to_local[0].y(), -world_to_local[0].z(), world_to_local[0].w()}; - - if (1) - { - btCollisionShape* box = new btBoxShape(baseHalfExtents); - btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(pMultiBody, -1); - col->setCollisionShape(box); - - btTransform tr; - tr.setIdentity(); - tr.setOrigin(local_origin[0]); - tr.setRotation(btQuaternion(quat[0], quat[1], quat[2], quat[3])); - col->setWorldTransform(tr); - - pWorld->addCollisionObject(col, 2, 1 + 2); - - col->setFriction(friction); - pMultiBody->setBaseCollider(col); - } - } - - for (int i = 0; i < pMultiBody->getNumLinks(); ++i) - { - const int parent = pMultiBody->getParent(i); - world_to_local[i + 1] = pMultiBody->getParentToLocalRot(i) * world_to_local[parent + 1]; - local_origin[i + 1] = local_origin[parent + 1] + (quatRotate(world_to_local[i + 1].inverse(), pMultiBody->getRVector(i))); - } - - for (int i = 0; i < pMultiBody->getNumLinks(); ++i) - { - btVector3 posr = local_origin[i + 1]; - // float pos[4]={posr.x(),posr.y(),posr.z(),1}; - - btScalar quat[4] = {-world_to_local[i + 1].x(), -world_to_local[i + 1].y(), -world_to_local[i + 1].z(), world_to_local[i + 1].w()}; - - btCollisionShape* box = new btBoxShape(linkHalfExtents); - btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(pMultiBody, i); - - col->setCollisionShape(box); - btTransform tr; - tr.setIdentity(); - tr.setOrigin(posr); - tr.setRotation(btQuaternion(quat[0], quat[1], quat[2], quat[3])); - col->setWorldTransform(tr); - col->setFriction(friction); - pWorld->addCollisionObject(col, 2, 1 + 2); - - pMultiBody->getLink(i).m_collider = col; - } -} -class CommonExampleInterface* DeformableContactCreateFunc(struct CommonExampleOptions& options) -{ - return new DeformableContact(options.m_guiHelper); -} - - diff --git a/examples/DeformableContact/DeformableContact.h b/examples/DeformableContact/DeformableContact.h deleted file mode 100644 index 591c6bab1..000000000 --- a/examples/DeformableContact/DeformableContact.h +++ /dev/null @@ -1,20 +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 _DEFORMABLE_CONTACT_H -#define _DEFORMABLE_CONTACT_H - -class CommonExampleInterface* DeformableContactCreateFunc(struct CommonExampleOptions& options); - -#endif //_DEFORMABLE_CONTACT_H diff --git a/examples/DeformableDemo/DeformableDemo.cpp b/examples/DeformableDemo/DeformableDemo.cpp deleted file mode 100644 index a3cdbf847..000000000 --- a/examples/DeformableDemo/DeformableDemo.cpp +++ /dev/null @@ -1,293 +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. -*/ - -///create 125 (5x5x5) dynamic object -#define ARRAY_SIZE_X 5 -#define ARRAY_SIZE_Y 5 -#define ARRAY_SIZE_Z 5 - -//maximum number of objects (and allow user to shoot additional boxes) -#define MAX_PROXIES (ARRAY_SIZE_X * ARRAY_SIZE_Y * ARRAY_SIZE_Z + 1024) - -///scaling of the objects (0.1 = 20 centimeter boxes ) -#define SCALING 1. -#define START_POS_X -5 -#define START_POS_Y -5 -#define START_POS_Z -3 - -#include "DeformableDemo.h" -///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files. -#include "btBulletDynamicsCommon.h" -#include "BulletSoftBody/btDeformableRigidDynamicsWorld.h" -#include "BulletSoftBody/btSoftBody.h" -#include "BulletSoftBody/btSoftBodyHelpers.h" -#include "BulletSoftBody/btDeformableBodySolver.h" -#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h" -#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" -#include //printf debugging - -#include "../CommonInterfaces/CommonRigidBodyBase.h" -#include "../Utils/b3ResourcePath.h" - -///The DeformableDemo shows the use of rolling friction. -///Spheres will come to a rest on a sloped plane using a constraint. Damping cannot achieve the same. -///Generally it is best to leave the rolling friction coefficient zero (or close to zero). -class DeformableDemo : public CommonRigidBodyBase -{ -public: - DeformableDemo(struct GUIHelperInterface* helper) - : CommonRigidBodyBase(helper) - { - } - virtual ~DeformableDemo() - { - } - void initPhysics(); - - void exitPhysics(); - - void resetCamera() - { - float dist = 20; - float pitch = -45; - float yaw = 100; - float targetPos[3] = {0, -3, 0}; - m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]); - } - - void stepSimulation(float deltaTime) - { - //use a smaller internal timestep, there are stability issues - float internalTimeStep = 1. / 240.f; - m_dynamicsWorld->stepSimulation(deltaTime, 4, internalTimeStep); - } - - void Ctor_RbUpStack(int count) - { - float mass = 0.2; - - btCompoundShape* cylinderCompound = new btCompoundShape; - btCollisionShape* cylinderShape = new btCylinderShapeX(btVector3(2, .5, .5)); - btCollisionShape* boxShape = new btBoxShape(btVector3(2, .5, .5)); - btTransform localTransform; - localTransform.setIdentity(); - cylinderCompound->addChildShape(localTransform, boxShape); - btQuaternion orn(SIMD_HALF_PI, 0, 0); - localTransform.setRotation(orn); - // localTransform.setOrigin(btVector3(1,1,1)); - cylinderCompound->addChildShape(localTransform, cylinderShape); - - btCollisionShape* shape[] = { - new btBoxShape(btVector3(1, 1, 1)), -// new btSphereShape(0.75), -// cylinderCompound - }; -// static const int nshapes = sizeof(shape) / sizeof(shape[0]); -// for (int i = 0; i < count; ++i) -// { -// btTransform startTransform; -// startTransform.setIdentity(); -// startTransform.setOrigin(btVector3(0, 2+ 2 * i, 0)); -// startTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0.)); -// createRigidBody(mass, startTransform, shape[i % nshapes]); -// } - btTransform startTransform; - startTransform.setIdentity(); - startTransform.setOrigin(btVector3(1, 1.5, 1)); - createRigidBody(mass, startTransform, shape[0]); - startTransform.setOrigin(btVector3(1, 1.5, -1)); - createRigidBody(mass, startTransform, shape[0]); - startTransform.setOrigin(btVector3(-1, 1.5, 1)); - createRigidBody(mass, startTransform, shape[0]); - startTransform.setOrigin(btVector3(-1, 1.5, -1)); - createRigidBody(mass, startTransform, shape[0]); - startTransform.setOrigin(btVector3(0, 3.5, 0)); - createRigidBody(mass, startTransform, shape[0]); - } - - virtual const btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() const - { - ///just make it a btSoftRigidDynamicsWorld please - ///or we will add type checking - return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; - } - - virtual btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() - { - ///just make it a btSoftRigidDynamicsWorld please - ///or we will add type checking - return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; - } - - virtual void renderScene() - { - CommonRigidBodyBase::renderScene(); - btDeformableRigidDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); - - for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++) - { - btSoftBody* psb = (btSoftBody*)deformableWorld->getSoftBodyArray()[i]; - //if (softWorld->getDebugDrawer() && !(softWorld->getDebugDrawer()->getDebugMode() & (btIDebugDraw::DBG_DrawWireframe))) - { - btSoftBodyHelpers::DrawFrame(psb, deformableWorld->getDebugDrawer()); - btSoftBodyHelpers::Draw(psb, deformableWorld->getDebugDrawer(), deformableWorld->getDrawFlags()); - } - } - } -}; - -void DeformableDemo::initPhysics() -{ - m_guiHelper->setUpAxis(1); - - ///collision configuration contains default setup for memory, collision setup - m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration(); - - ///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(); - btDeformableBodySolver* deformableBodySolver = new btDeformableBodySolver(); - - ///the default constraint solver. For parallel processing you can use a different solver (see Extras/BulletMultiThreaded) - btMultiBodyConstraintSolver* sol = new btMultiBodyConstraintSolver(); - m_solver = sol; - - m_dynamicsWorld = new btDeformableRigidDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); - deformableBodySolver->setWorld(getDeformableDynamicsWorld()); - // m_dynamicsWorld->getSolverInfo().m_singleAxisDeformableThreshold = 0.f;//faster but lower quality - btVector3 gravity = btVector3(0, -10, 0); - m_dynamicsWorld->setGravity(gravity); - getDeformableDynamicsWorld()->getWorldInfo().m_gravity = gravity; - -// getDeformableDynamicsWorld()->before_solver_callbacks.push_back(dynamics); - m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); - - { - ///create a ground - btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(150.), btScalar(25.), btScalar(150.))); - - m_collisionShapes.push_back(groundShape); - - btTransform groundTransform; - groundTransform.setIdentity(); - groundTransform.setOrigin(btVector3(0, -32, 0)); - groundTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0.)); - //We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here: - btScalar mass(0.); - - //rigidbody is dynamic if and only if mass is non zero, otherwise static - bool isDynamic = (mass != 0.f); - - btVector3 localInertia(0, 0, 0); - if (isDynamic) - groundShape->calculateLocalInertia(mass, localInertia); - - //using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects - btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform); - btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia); - btRigidBody* body = new btRigidBody(rbInfo); - body->setFriction(1); - - //add the ground to the dynamics world - m_dynamicsWorld->addRigidBody(body); - } - - // create a piece of cloth - { - bool onGround = false; - const btScalar s = 4; - btSoftBody* psb = btSoftBodyHelpers::CreatePatch(getDeformableDynamicsWorld()->getWorldInfo(), btVector3(-s, 0, -s), - btVector3(+s, 0, -s), - btVector3(-s, 0, +s), - btVector3(+s, 0, +s), -// 3,3, - 20,20, - 1 + 2 + 4 + 8, true); -// 0, true); - - if (onGround) - psb = btSoftBodyHelpers::CreatePatch(getDeformableDynamicsWorld()->getWorldInfo(), btVector3(-s, 0, -s), - btVector3(+s, 0, -s), - btVector3(-s, 0, +s), - btVector3(+s, 0, +s), -// 20,20, - 2,2, - 0, true); - - psb->getCollisionShape()->setMargin(0.1); - psb->generateBendingConstraints(2); - psb->setTotalMass(1); - psb->setSpringStiffness(1); - psb->setDampingCoefficient(0.01); - psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects - psb->m_cfg.kCHR = 1; // collision hardness with rigid body - psb->m_cfg.kDF = 1; - psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; - getDeformableDynamicsWorld()->addSoftBody(psb); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce()); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); - - // add a few rigid bodies - Ctor_RbUpStack(1); - } - m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); -} - -void DeformableDemo::exitPhysics() -{ - //cleanup in the reverse order of creation/initialization - - //remove the rigidbodies from the dynamics world and delete them - int i; - for (i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--) - { - btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i]; - btRigidBody* body = btRigidBody::upcast(obj); - if (body && body->getMotionState()) - { - delete body->getMotionState(); - } - m_dynamicsWorld->removeCollisionObject(obj); - delete obj; - } - - //delete collision shapes - for (int j = 0; j < m_collisionShapes.size(); j++) - { - btCollisionShape* shape = m_collisionShapes[j]; - delete shape; - } - m_collisionShapes.clear(); - - delete m_dynamicsWorld; - - delete m_solver; - - delete m_broadphase; - - delete m_dispatcher; - - delete m_collisionConfiguration; -} - - - -class CommonExampleInterface* DeformableCreateFunc(struct CommonExampleOptions& options) -{ - return new DeformableDemo(options.m_guiHelper); -} - - diff --git a/examples/DeformableDemo/DeformableDemo.h b/examples/DeformableDemo/DeformableDemo.h deleted file mode 100644 index c688cea9d..000000000 --- a/examples/DeformableDemo/DeformableDemo.h +++ /dev/null @@ -1,20 +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 _DEFORMABLE_DEMO_H -#define _DEFORMABLE_DEMO_H - -class CommonExampleInterface* DeformableCreateFunc(struct CommonExampleOptions& options); - -#endif //_DEFORMABLE_DEMO_H diff --git a/examples/DeformableDemo/DeformableMultibody.cpp b/examples/DeformableDemo/DeformableMultibody.cpp new file mode 100644 index 000000000..78adf7bf1 --- /dev/null +++ b/examples/DeformableDemo/DeformableMultibody.cpp @@ -0,0 +1,409 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2016 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. + */ + +///create 125 (5x5x5) dynamic object +#define ARRAY_SIZE_X 5 +#define ARRAY_SIZE_Y 5 +#define ARRAY_SIZE_Z 5 + +//maximum number of objects (and allow user to shoot additional boxes) +#define MAX_PROXIES (ARRAY_SIZE_X * ARRAY_SIZE_Y * ARRAY_SIZE_Z + 1024) + +///scaling of the objects (0.1 = 20 centimeter boxes ) +#define SCALING 1. +#define START_POS_X -5 +#define START_POS_Y -5 +#define START_POS_Z -3 + +#include "DeformableMultibody.h" +///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files. +#include "btBulletDynamicsCommon.h" +#include "BulletSoftBody/btDeformableRigidDynamicsWorld.h" +#include "BulletSoftBody/btSoftBody.h" +#include "BulletSoftBody/btSoftBodyHelpers.h" +#include "BulletSoftBody/btDeformableBodySolver.h" +#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h" +#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" +#include //printf debugging + +#include "../CommonInterfaces/CommonRigidBodyBase.h" +#include "../Utils/b3ResourcePath.h" +#include "../SoftDemo/BunnyMesh.h" +#include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h" +#include "BulletDynamics/Featherstone/btMultiBodyJointFeedback.h" + +#include "../CommonInterfaces/CommonMultiBodyBase.h" +#include "../Utils/b3ResourcePath.h" +///The DeformableMultibody demo deformable bodies self-collision +static bool g_floatingBase = true; +static float friction = 1.; +class DeformableMultibody : public CommonMultiBodyBase +{ + btMultiBody* m_multiBody; + btAlignedObjectArray m_jointFeedbacks; +public: + DeformableMultibody(struct GUIHelperInterface* helper) + : CommonMultiBodyBase(helper) + { + } + + virtual ~DeformableMultibody() + { + } + + void initPhysics(); + + void exitPhysics(); + + void resetCamera() + { + float dist = 30; + float pitch = -30; + float yaw = 100; + float targetPos[3] = {0, -10, 0}; + m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]); + } + + virtual void stepSimulation(float deltaTime); + + btMultiBody* createFeatherstoneMultiBody_testMultiDof(class btMultiBodyDynamicsWorld* world, int numLinks, const btVector3& basePosition, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents, bool spherical = false, bool floating = false); + + void addColliders_testMultiDof(btMultiBody* pMultiBody, btMultiBodyDynamicsWorld* pWorld, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents); + + + virtual const btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() const + { + return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; + } + + virtual btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() + { + return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; + } + + virtual void renderScene() + { + CommonMultiBodyBase::renderScene(); + btDeformableRigidDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); + + for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++) + { + btSoftBody* psb = (btSoftBody*)deformableWorld->getSoftBodyArray()[i]; + { + btSoftBodyHelpers::DrawFrame(psb, deformableWorld->getDebugDrawer()); + btSoftBodyHelpers::Draw(psb, deformableWorld->getDebugDrawer(), deformableWorld->getDrawFlags()); + } + } + } +}; + +void DeformableMultibody::initPhysics() +{ + m_guiHelper->setUpAxis(1); + + ///collision configuration contains default setup for memory, collision setup + m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration(); + + ///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(); + btDeformableBodySolver* deformableBodySolver = new btDeformableBodySolver(); + btMultiBodyConstraintSolver* sol; + sol = new btMultiBodyConstraintSolver; + m_solver = sol; + + m_dynamicsWorld = new btDeformableRigidDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); + deformableBodySolver->setWorld(getDeformableDynamicsWorld()); + btVector3 gravity = btVector3(0, -10, 0); + m_dynamicsWorld->setGravity(gravity); + getDeformableDynamicsWorld()->getWorldInfo().m_gravity = gravity; + m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); + + { + ///create a ground + btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(150.), btScalar(25.), btScalar(150.))); + + m_collisionShapes.push_back(groundShape); + + btTransform groundTransform; + groundTransform.setIdentity(); + groundTransform.setOrigin(btVector3(0, -40, 0)); + groundTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0.)); + //We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here: + btScalar mass(0.); + + //rigidbody is dynamic if and only if mass is non zero, otherwise static + bool isDynamic = (mass != 0.f); + + btVector3 localInertia(0, 0, 0); + if (isDynamic) + groundShape->calculateLocalInertia(mass, localInertia); + + //using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects + btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform); + btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia); + btRigidBody* body = new btRigidBody(rbInfo); + body->setFriction(0.5); + + //add the ground to the dynamics world + m_dynamicsWorld->addRigidBody(body,1,1+2); + } + + + { + bool damping = true; + bool gyro = false; + int numLinks = 4; + bool spherical = false; //set it ot false -to use 1DoF hinges instead of 3DoF sphericals + bool canSleep = false; + bool selfCollide = true; + btVector3 linkHalfExtents(.4, 1, .4); + btVector3 baseHalfExtents(.4, 1, .4); + + btMultiBody* mbC = createFeatherstoneMultiBody_testMultiDof(m_dynamicsWorld, numLinks, btVector3(0.f, 10.f,0.f), linkHalfExtents, baseHalfExtents, spherical, g_floatingBase); + + mbC->setCanSleep(canSleep); + mbC->setHasSelfCollision(selfCollide); + mbC->setUseGyroTerm(gyro); + // + if (!damping) + { + mbC->setLinearDamping(0.0f); + mbC->setAngularDamping(0.0f); + } + else + { + mbC->setLinearDamping(0.04f); + mbC->setAngularDamping(0.04f); + } + + if (numLinks > 0) + { + btScalar q0 = 0.f * SIMD_PI / 180.f; + if (!spherical) + { + mbC->setJointPosMultiDof(0, &q0); + } + else + { + btQuaternion quat0(btVector3(1, 1, 0).normalized(), q0); + quat0.normalize(); + mbC->setJointPosMultiDof(0, quat0); + } + } + /// + addColliders_testMultiDof(mbC, m_dynamicsWorld, baseHalfExtents, linkHalfExtents); + } + + // create a patch of cloth + { + btScalar h = 0; + const btScalar s = 4; + btSoftBody* psb = btSoftBodyHelpers::CreatePatch(getDeformableDynamicsWorld()->getWorldInfo(), btVector3(-s, h, -s), + btVector3(+s, h, -s), + btVector3(-s, h, +s), + btVector3(+s, h, +s), + 20,20, +// 3,3, + 1 + 2 + 4 + 8, true); + + psb->getCollisionShape()->setMargin(0.25); + psb->generateBendingConstraints(2); + psb->setTotalMass(5); + psb->setSpringStiffness(2); + psb->setDampingCoefficient(0.01); + psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects + psb->m_cfg.kCHR = 1; // collision hardness with rigid body + psb->m_cfg.kDF = .1; + psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; + getDeformableDynamicsWorld()->addSoftBody(psb); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce()); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); + } + + m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); +} + +void DeformableMultibody::exitPhysics() +{ + //cleanup in the reverse order of creation/initialization + + //remove the rigidbodies from the dynamics world and delete them + int i; + for (i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--) + { + btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i]; + btRigidBody* body = btRigidBody::upcast(obj); + if (body && body->getMotionState()) + { + delete body->getMotionState(); + } + m_dynamicsWorld->removeCollisionObject(obj); + delete obj; + } + + //delete collision shapes + for (int j = 0; j < m_collisionShapes.size(); j++) + { + btCollisionShape* shape = m_collisionShapes[j]; + delete shape; + } + m_collisionShapes.clear(); + + delete m_dynamicsWorld; + + delete m_solver; + + delete m_broadphase; + + delete m_dispatcher; + + delete m_collisionConfiguration; +} + +void DeformableMultibody::stepSimulation(float deltaTime) +{ +// getDeformableDynamicsWorld()->getMultiBodyDynamicsWorld()->stepSimulation(deltaTime); + m_dynamicsWorld->stepSimulation(deltaTime, 5, 1./250.); +} + + +btMultiBody* DeformableMultibody::createFeatherstoneMultiBody_testMultiDof(btMultiBodyDynamicsWorld* pWorld, int numLinks, const btVector3& basePosition, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents, bool spherical, bool floating) +{ + //init the base + btVector3 baseInertiaDiag(0.f, 0.f, 0.f); + float baseMass = .1f; + + if (baseMass) + { + btCollisionShape* pTempBox = new btBoxShape(btVector3(baseHalfExtents[0], baseHalfExtents[1], baseHalfExtents[2])); + pTempBox->calculateLocalInertia(baseMass, baseInertiaDiag); + delete pTempBox; + } + + bool canSleep = false; + + btMultiBody* pMultiBody = new btMultiBody(numLinks, baseMass, baseInertiaDiag, !floating, canSleep); + + btQuaternion baseOriQuat(0.f, 0.f, 0.f, 1.f); + pMultiBody->setBasePos(basePosition); + pMultiBody->setWorldToBaseRot(baseOriQuat); + btVector3 vel(0, 0, 0); + // pMultiBody->setBaseVel(vel); + + //init the links + btVector3 hingeJointAxis(1, 0, 0); + float linkMass = .1f; + btVector3 linkInertiaDiag(0.f, 0.f, 0.f); + + btCollisionShape* pTempBox = new btBoxShape(btVector3(linkHalfExtents[0], linkHalfExtents[1], linkHalfExtents[2])); + pTempBox->calculateLocalInertia(linkMass, linkInertiaDiag); + delete pTempBox; + + //y-axis assumed up + btVector3 parentComToCurrentCom(0, -linkHalfExtents[1] * 2.f, 0); //par body's COM to cur body's COM offset + btVector3 currentPivotToCurrentCom(0, -linkHalfExtents[1], 0); //cur body's COM to cur body's PIV offset + btVector3 parentComToCurrentPivot = parentComToCurrentCom - currentPivotToCurrentCom; //par body's COM to cur body's PIV offset + + ////// + btScalar q0 = 0.f * SIMD_PI / 180.f; + btQuaternion quat0(btVector3(0, 1, 0).normalized(), q0); + quat0.normalize(); + ///// + + for (int i = 0; i < numLinks; ++i) + { + if (!spherical) + pMultiBody->setupRevolute(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f), hingeJointAxis, parentComToCurrentPivot, currentPivotToCurrentCom, true); + else + //pMultiBody->setupPlanar(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f)/*quat0*/, btVector3(1, 0, 0), parentComToCurrentPivot*2, false); + pMultiBody->setupSpherical(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f), parentComToCurrentPivot, currentPivotToCurrentCom, true); + } + + pMultiBody->finalizeMultiDof(); + + /// + pWorld->addMultiBody(pMultiBody); + /// + return pMultiBody; +} + +void DeformableMultibody::addColliders_testMultiDof(btMultiBody* pMultiBody, btMultiBodyDynamicsWorld* pWorld, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents) +{ + btAlignedObjectArray world_to_local; + world_to_local.resize(pMultiBody->getNumLinks() + 1); + + btAlignedObjectArray local_origin; + local_origin.resize(pMultiBody->getNumLinks() + 1); + world_to_local[0] = pMultiBody->getWorldToBaseRot(); + local_origin[0] = pMultiBody->getBasePos(); + + { + // float pos[4]={local_origin[0].x(),local_origin[0].y(),local_origin[0].z(),1}; + btScalar quat[4] = {-world_to_local[0].x(), -world_to_local[0].y(), -world_to_local[0].z(), world_to_local[0].w()}; + + if (1) + { + btCollisionShape* box = new btBoxShape(baseHalfExtents); + btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(pMultiBody, -1); + col->setCollisionShape(box); + + btTransform tr; + tr.setIdentity(); + tr.setOrigin(local_origin[0]); + tr.setRotation(btQuaternion(quat[0], quat[1], quat[2], quat[3])); + col->setWorldTransform(tr); + + pWorld->addCollisionObject(col, 2, 1 + 2); + + col->setFriction(friction); + pMultiBody->setBaseCollider(col); + } + } + + for (int i = 0; i < pMultiBody->getNumLinks(); ++i) + { + const int parent = pMultiBody->getParent(i); + world_to_local[i + 1] = pMultiBody->getParentToLocalRot(i) * world_to_local[parent + 1]; + local_origin[i + 1] = local_origin[parent + 1] + (quatRotate(world_to_local[i + 1].inverse(), pMultiBody->getRVector(i))); + } + + for (int i = 0; i < pMultiBody->getNumLinks(); ++i) + { + btVector3 posr = local_origin[i + 1]; + // float pos[4]={posr.x(),posr.y(),posr.z(),1}; + + btScalar quat[4] = {-world_to_local[i + 1].x(), -world_to_local[i + 1].y(), -world_to_local[i + 1].z(), world_to_local[i + 1].w()}; + + btCollisionShape* box = new btBoxShape(linkHalfExtents); + btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(pMultiBody, i); + + col->setCollisionShape(box); + btTransform tr; + tr.setIdentity(); + tr.setOrigin(posr); + tr.setRotation(btQuaternion(quat[0], quat[1], quat[2], quat[3])); + col->setWorldTransform(tr); + col->setFriction(friction); + pWorld->addCollisionObject(col, 2, 1 + 2); + + pMultiBody->getLink(i).m_collider = col; + } +} +class CommonExampleInterface* DeformableMultibodyCreateFunc(struct CommonExampleOptions& options) +{ + return new DeformableMultibody(options.m_guiHelper); +} + + diff --git a/examples/DeformableDemo/DeformableMultibody.h b/examples/DeformableDemo/DeformableMultibody.h new file mode 100644 index 000000000..8bc9020f3 --- /dev/null +++ b/examples/DeformableDemo/DeformableMultibody.h @@ -0,0 +1,19 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2016 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 _DEFORMABLE_MULTIBODY_H +#define _DEFORMABLE_MULTIBODY_H + +class CommonExampleInterface* DeformableMultibodyCreateFunc(struct CommonExampleOptions& options); + +#endif //_DEFORMABLE_MULTIBODY_H diff --git a/examples/DeformableDemo/DeformableRigid.cpp b/examples/DeformableDemo/DeformableRigid.cpp new file mode 100644 index 000000000..c26bcc7d5 --- /dev/null +++ b/examples/DeformableDemo/DeformableRigid.cpp @@ -0,0 +1,291 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2016 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. + */ + +///create 125 (5x5x5) dynamic object +#define ARRAY_SIZE_X 5 +#define ARRAY_SIZE_Y 5 +#define ARRAY_SIZE_Z 5 + +//maximum number of objects (and allow user to shoot additional boxes) +#define MAX_PROXIES (ARRAY_SIZE_X * ARRAY_SIZE_Y * ARRAY_SIZE_Z + 1024) + +///scaling of the objects (0.1 = 20 centimeter boxes ) +#define SCALING 1. +#define START_POS_X -5 +#define START_POS_Y -5 +#define START_POS_Z -3 + +#include "DeformableRigid.h" +///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files. +#include "btBulletDynamicsCommon.h" +#include "BulletSoftBody/btDeformableRigidDynamicsWorld.h" +#include "BulletSoftBody/btSoftBody.h" +#include "BulletSoftBody/btSoftBodyHelpers.h" +#include "BulletSoftBody/btDeformableBodySolver.h" +#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h" +#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" +#include //printf debugging + +#include "../CommonInterfaces/CommonRigidBodyBase.h" +#include "../Utils/b3ResourcePath.h" + +///The DeformableRigid shows the use of rolling friction. +///Spheres will come to a rest on a sloped plane using a constraint. Damping cannot achieve the same. +///Generally it is best to leave the rolling friction coefficient zero (or close to zero). +class DeformableRigid : public CommonRigidBodyBase +{ +public: + DeformableRigid(struct GUIHelperInterface* helper) + : CommonRigidBodyBase(helper) + { + } + virtual ~DeformableRigid() + { + } + void initPhysics(); + + void exitPhysics(); + + void resetCamera() + { + float dist = 20; + float pitch = -45; + float yaw = 100; + float targetPos[3] = {0, -3, 0}; + m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]); + } + + void stepSimulation(float deltaTime) + { + //use a smaller internal timestep, there are stability issues + float internalTimeStep = 1. / 240.f; + m_dynamicsWorld->stepSimulation(deltaTime, 4, internalTimeStep); + } + + void Ctor_RbUpStack(int count) + { + float mass = 0.2; + + btCompoundShape* cylinderCompound = new btCompoundShape; + btCollisionShape* cylinderShape = new btCylinderShapeX(btVector3(2, .5, .5)); + btCollisionShape* boxShape = new btBoxShape(btVector3(2, .5, .5)); + btTransform localTransform; + localTransform.setIdentity(); + cylinderCompound->addChildShape(localTransform, boxShape); + btQuaternion orn(SIMD_HALF_PI, 0, 0); + localTransform.setRotation(orn); + // localTransform.setOrigin(btVector3(1,1,1)); + cylinderCompound->addChildShape(localTransform, cylinderShape); + + btCollisionShape* shape[] = { + new btBoxShape(btVector3(1, 1, 1)), +// new btSphereShape(0.75), +// cylinderCompound + }; +// static const int nshapes = sizeof(shape) / sizeof(shape[0]); +// for (int i = 0; i < count; ++i) +// { +// btTransform startTransform; +// startTransform.setIdentity(); +// startTransform.setOrigin(btVector3(0, 2+ 2 * i, 0)); +// startTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0.)); +// createRigidBody(mass, startTransform, shape[i % nshapes]); +// } + btTransform startTransform; + startTransform.setIdentity(); + startTransform.setOrigin(btVector3(1, 1.5, 1)); + createRigidBody(mass, startTransform, shape[0]); + startTransform.setOrigin(btVector3(1, 1.5, -1)); + createRigidBody(mass, startTransform, shape[0]); + startTransform.setOrigin(btVector3(-1, 1.5, 1)); + createRigidBody(mass, startTransform, shape[0]); + startTransform.setOrigin(btVector3(-1, 1.5, -1)); + createRigidBody(mass, startTransform, shape[0]); + startTransform.setOrigin(btVector3(0, 3.5, 0)); + createRigidBody(mass, startTransform, shape[0]); + } + + virtual const btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() const + { + ///just make it a btSoftRigidDynamicsWorld please + ///or we will add type checking + return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; + } + + virtual btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() + { + ///just make it a btSoftRigidDynamicsWorld please + ///or we will add type checking + return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; + } + + virtual void renderScene() + { + CommonRigidBodyBase::renderScene(); + btDeformableRigidDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); + + for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++) + { + btSoftBody* psb = (btSoftBody*)deformableWorld->getSoftBodyArray()[i]; + //if (softWorld->getDebugDrawer() && !(softWorld->getDebugDrawer()->getDebugMode() & (btIDebugDraw::DBG_DrawWireframe))) + { + btSoftBodyHelpers::DrawFrame(psb, deformableWorld->getDebugDrawer()); + btSoftBodyHelpers::Draw(psb, deformableWorld->getDebugDrawer(), deformableWorld->getDrawFlags()); + } + } + } +}; + +void DeformableRigid::initPhysics() +{ + m_guiHelper->setUpAxis(1); + + ///collision configuration contains default setup for memory, collision setup + m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration(); + + ///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(); + btDeformableBodySolver* deformableBodySolver = new btDeformableBodySolver(); + + ///the default constraint solver. For parallel processing you can use a different solver (see Extras/BulletMultiThreaded) + btMultiBodyConstraintSolver* sol = new btMultiBodyConstraintSolver(); + m_solver = sol; + + m_dynamicsWorld = new btDeformableRigidDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); + deformableBodySolver->setWorld(getDeformableDynamicsWorld()); + // m_dynamicsWorld->getSolverInfo().m_singleAxisDeformableThreshold = 0.f;//faster but lower quality + btVector3 gravity = btVector3(0, -10, 0); + m_dynamicsWorld->setGravity(gravity); + getDeformableDynamicsWorld()->getWorldInfo().m_gravity = gravity; + +// getDeformableDynamicsWorld()->before_solver_callbacks.push_back(dynamics); + m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); + + { + ///create a ground + btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(150.), btScalar(25.), btScalar(150.))); + + m_collisionShapes.push_back(groundShape); + + btTransform groundTransform; + groundTransform.setIdentity(); + groundTransform.setOrigin(btVector3(0, -32, 0)); + groundTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0.)); + //We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here: + btScalar mass(0.); + + //rigidbody is dynamic if and only if mass is non zero, otherwise static + bool isDynamic = (mass != 0.f); + + btVector3 localInertia(0, 0, 0); + if (isDynamic) + groundShape->calculateLocalInertia(mass, localInertia); + + //using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects + btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform); + btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia); + btRigidBody* body = new btRigidBody(rbInfo); + body->setFriction(1); + + //add the ground to the dynamics world + m_dynamicsWorld->addRigidBody(body); + } + + // create a piece of cloth + { + bool onGround = false; + const btScalar s = 4; + btSoftBody* psb = btSoftBodyHelpers::CreatePatch(getDeformableDynamicsWorld()->getWorldInfo(), btVector3(-s, 0, -s), + btVector3(+s, 0, -s), + btVector3(-s, 0, +s), + btVector3(+s, 0, +s), +// 3,3, + 20,20, + 1 + 2 + 4 + 8, true); +// 0, true); + + if (onGround) + psb = btSoftBodyHelpers::CreatePatch(getDeformableDynamicsWorld()->getWorldInfo(), btVector3(-s, 0, -s), + btVector3(+s, 0, -s), + btVector3(-s, 0, +s), + btVector3(+s, 0, +s), +// 20,20, + 2,2, + 0, true); + + psb->getCollisionShape()->setMargin(0.1); + psb->generateBendingConstraints(2); + psb->setTotalMass(1); + psb->setSpringStiffness(1); + psb->setDampingCoefficient(0.01); + psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects + psb->m_cfg.kCHR = 1; // collision hardness with rigid body + psb->m_cfg.kDF = 1; + psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; + getDeformableDynamicsWorld()->addSoftBody(psb); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce()); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); + + // add a few rigid bodies + Ctor_RbUpStack(1); + } + m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); +} + +void DeformableRigid::exitPhysics() +{ + //cleanup in the reverse order of creation/initialization + + //remove the rigidbodies from the dynamics world and delete them + int i; + for (i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--) + { + btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i]; + btRigidBody* body = btRigidBody::upcast(obj); + if (body && body->getMotionState()) + { + delete body->getMotionState(); + } + m_dynamicsWorld->removeCollisionObject(obj); + delete obj; + } + + //delete collision shapes + for (int j = 0; j < m_collisionShapes.size(); j++) + { + btCollisionShape* shape = m_collisionShapes[j]; + delete shape; + } + m_collisionShapes.clear(); + + delete m_dynamicsWorld; + + delete m_solver; + + delete m_broadphase; + + delete m_dispatcher; + + delete m_collisionConfiguration; +} + + + +class CommonExampleInterface* DeformableRigidCreateFunc(struct CommonExampleOptions& options) +{ + return new DeformableRigid(options.m_guiHelper); +} + + diff --git a/examples/DeformableDemo/DeformableRigid.h b/examples/DeformableDemo/DeformableRigid.h new file mode 100644 index 000000000..1f2bb0911 --- /dev/null +++ b/examples/DeformableDemo/DeformableRigid.h @@ -0,0 +1,19 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2016 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 _DEFORMABLE_RIGID_H +#define _DEFORMABLE_RIGID_H + +class CommonExampleInterface* DeformableRigidCreateFunc(struct CommonExampleOptions& options); + +#endif //_DEFORMABLE_RIGID_H diff --git a/examples/DeformableDemo/Pinch.cpp b/examples/DeformableDemo/Pinch.cpp new file mode 100644 index 000000000..aaae1df3f --- /dev/null +++ b/examples/DeformableDemo/Pinch.cpp @@ -0,0 +1,397 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2016 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. + */ + +///create 125 (5x5x5) dynamic object +#define ARRAY_SIZE_X 5 +#define ARRAY_SIZE_Y 5 +#define ARRAY_SIZE_Z 5 + +//maximum number of objects (and allow user to shoot additional boxes) +#define MAX_PROXIES (ARRAY_SIZE_X * ARRAY_SIZE_Y * ARRAY_SIZE_Z + 1024) + +///scaling of the objects (0.1 = 20 centimeter boxes ) +#define SCALING 1. +#define START_POS_X -5 +#define START_POS_Y -5 +#define START_POS_Z -3 + +#include "Pinch.h" +///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files. +#include "btBulletDynamicsCommon.h" +#include "BulletSoftBody/btDeformableRigidDynamicsWorld.h" +#include "BulletSoftBody/btSoftBody.h" +#include "BulletSoftBody/btSoftBodyHelpers.h" +#include "BulletSoftBody/btDeformableBodySolver.h" +#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h" +#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" +#include //printf debugging + +#include "../CommonInterfaces/CommonRigidBodyBase.h" +#include "../Utils/b3ResourcePath.h" + +///The Pinch shows the use of rolling friction. +///Spheres will come to a rest on a sloped plane using a constraint. Damping cannot achieve the same. +///Generally it is best to leave the rolling friction coefficient zero (or close to zero). + +struct TetraCube +{ +#include "../SoftDemo/cube.inl" +}; + +struct TetraBunny +{ +#include "../SoftDemo/bunny.inl" +}; + + +class Pinch : public CommonRigidBodyBase +{ +public: + Pinch(struct GUIHelperInterface* helper) + : CommonRigidBodyBase(helper) + { + } + virtual ~Pinch() + { + } + void initPhysics(); + + void exitPhysics(); + + void resetCamera() + { + float dist = 25; + float pitch = -30; + float yaw = 100; + float targetPos[3] = {0, -0, 0}; + m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]); + } + + void stepSimulation(float deltaTime) + { + //use a smaller internal timestep, there are stability issues + float internalTimeStep = 1. / 240.f; + m_dynamicsWorld->stepSimulation(deltaTime, 4, internalTimeStep); + } + + void createGrip() + { + int count = 2; + float mass = 2; + btCollisionShape* shape[] = { + new btBoxShape(btVector3(3, 3, 0.5)), + }; + static const int nshapes = sizeof(shape) / sizeof(shape[0]); + for (int i = 0; i < count; ++i) + { + btTransform startTransform; + startTransform.setIdentity(); + startTransform.setOrigin(btVector3(10, 0, 0)); + startTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0.)); + createRigidBody(mass, startTransform, shape[i % nshapes]); + } + } + + virtual const btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() const + { + return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; + } + + virtual btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() + { + return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; + } + + virtual void renderScene() + { + CommonRigidBodyBase::renderScene(); + btDeformableRigidDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); + + for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++) + { + btSoftBody* psb = (btSoftBody*)deformableWorld->getSoftBodyArray()[i]; + { + btSoftBodyHelpers::DrawFrame(psb, deformableWorld->getDebugDrawer()); + btSoftBodyHelpers::Draw(psb, deformableWorld->getDebugDrawer(), deformableWorld->getDrawFlags()); + } + } + } +}; + +void dynamics(btScalar time, btDeformableRigidDynamicsWorld* world) +{ + btAlignedObjectArray& rbs = world->getNonStaticRigidBodies(); + if (rbs.size()<2) + return; + btRigidBody* rb0 = rbs[0]; + btScalar pressTime = 0.9; + btScalar liftTime = 2.5; + btScalar shiftTime = 3.5; + btScalar holdTime = 4.5*1000; + btScalar dropTime = 5.3*1000; + btTransform rbTransform; + rbTransform.setIdentity(); + btVector3 translation; + btVector3 velocity; + + btVector3 initialTranslationLeft = btVector3(0.5,3,4); + btVector3 initialTranslationRight = btVector3(0.5,3,-4); + btVector3 pinchVelocityLeft = btVector3(0,0,-2); + btVector3 pinchVelocityRight = btVector3(0,0,2); + btVector3 liftVelocity = btVector3(0,5,0); + btVector3 shiftVelocity = btVector3(0,0,5); + btVector3 holdVelocity = btVector3(0,0,0); + btVector3 openVelocityLeft = btVector3(0,0,4); + btVector3 openVelocityRight = btVector3(0,0,-4); + + if (time < pressTime) + { + velocity = pinchVelocityLeft; + translation = initialTranslationLeft + pinchVelocityLeft * time; + } + else if (time < liftTime) + { + velocity = liftVelocity; + translation = initialTranslationLeft + pinchVelocityLeft * pressTime + liftVelocity * (time - pressTime); + + } + else if (time < shiftTime) + { + velocity = shiftVelocity; + translation = initialTranslationLeft + pinchVelocityLeft * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (time - liftTime); + } + else if (time < holdTime) + { + velocity = btVector3(0,0,0); + translation = initialTranslationLeft + pinchVelocityLeft * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (shiftTime - liftTime) + holdVelocity * (time - shiftTime); + } + else if (time < dropTime) + { + velocity = openVelocityLeft; + translation = initialTranslationLeft + pinchVelocityLeft * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (shiftTime - liftTime) + holdVelocity * (holdTime - shiftTime)+ openVelocityLeft * (time - holdTime); + } + else + { + velocity = holdVelocity; + translation = initialTranslationLeft + pinchVelocityLeft * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (shiftTime - liftTime) + holdVelocity * (holdTime - shiftTime)+ openVelocityLeft * (dropTime - holdTime); + } + rbTransform.setOrigin(translation); + rbTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0)); + rb0->setCenterOfMassTransform(rbTransform); + rb0->setAngularVelocity(btVector3(0,0,0)); + rb0->setLinearVelocity(velocity); + + btRigidBody* rb1 = rbs[1]; + if (time < pressTime) + { + velocity = pinchVelocityRight; + translation = initialTranslationRight + pinchVelocityRight * time; + } + else if (time < liftTime) + { + velocity = liftVelocity; + translation = initialTranslationRight + pinchVelocityRight * pressTime + liftVelocity * (time - pressTime); + + } + else if (time < shiftTime) + { + velocity = shiftVelocity; + translation = initialTranslationRight + pinchVelocityRight * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (time - liftTime); + } + else if (time < holdTime) + { + velocity = btVector3(0,0,0); + translation = initialTranslationRight + pinchVelocityRight * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (shiftTime - liftTime) + holdVelocity * (time - shiftTime); + } + else if (time < dropTime) + { + velocity = openVelocityRight; + translation = initialTranslationRight + pinchVelocityRight * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (shiftTime - liftTime) + holdVelocity * (holdTime - shiftTime)+ openVelocityRight * (time - holdTime); + } + else + { + velocity = holdVelocity; + translation = initialTranslationRight + pinchVelocityRight * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (shiftTime - liftTime) + holdVelocity * (holdTime - shiftTime)+ openVelocityRight * (dropTime - holdTime); + } + rbTransform.setOrigin(translation); + rbTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0)); + rb1->setCenterOfMassTransform(rbTransform); + rb1->setAngularVelocity(btVector3(0,0,0)); + rb1->setLinearVelocity(velocity); + + rb0->setFriction(20); + rb1->setFriction(20); +} + +void Pinch::initPhysics() +{ + m_guiHelper->setUpAxis(1); + + m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration(); + + m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration); + + m_broadphase = new btDbvtBroadphase(); + btDeformableBodySolver* deformableBodySolver = new btDeformableBodySolver(); + + btMultiBodyConstraintSolver* sol = new btMultiBodyConstraintSolver(); + m_solver = sol; + + m_dynamicsWorld = new btDeformableRigidDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); + deformableBodySolver->setWorld(getDeformableDynamicsWorld()); + // m_dynamicsWorld->getSolverInfo().m_singleAxisDeformableThreshold = 0.f;//faster but lower quality + btVector3 gravity = btVector3(0, -10, 0); + m_dynamicsWorld->setGravity(gravity); + getDeformableDynamicsWorld()->getWorldInfo().m_gravity = gravity; + + getDeformableDynamicsWorld()->setSolverCallback(dynamics); + m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); + + //create a ground + { + btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(150.), btScalar(25.), btScalar(150.))); + + m_collisionShapes.push_back(groundShape); + + btTransform groundTransform; + groundTransform.setIdentity(); + groundTransform.setOrigin(btVector3(0, -25, 0)); + groundTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0)); + //We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here: + btScalar mass(0.); + + //rigidbody is dynamic if and only if mass is non zero, otherwise static + bool isDynamic = (mass != 0.f); + + btVector3 localInertia(0, 0, 0); + if (isDynamic) + groundShape->calculateLocalInertia(mass, localInertia); + + //using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects + btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform); + btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia); + btRigidBody* body = new btRigidBody(rbInfo); + body->setFriction(0.5); + + //add the ground to the dynamics world + m_dynamicsWorld->addRigidBody(body); + } + + // create a soft block + { + btScalar verts[24] = {0.f, 0.f, 0.f, + 1.f, 0.f, 0.f, + 0.f, 1.f, 0.f, + 0.f, 0.f, 1.f, + 1.f, 1.f, 0.f, + 0.f, 1.f, 1.f, + 1.f, 0.f, 1.f, + 1.f, 1.f, 1.f + }; + int triangles[60] = {0, 6, 3, + 0,1,6, + 7,5,3, + 7,3,6, + 4,7,6, + 4,6,1, + 7,2,5, + 7,4,2, + 0,3,2, + 2,3,5, + 0,2,4, + 0,4,1, + 0,6,5, + 0,6,4, + 3,4,2, + 3,4,7, + 2,7,3, + 2,7,1, + 4,5,0, + 4,5,6, + }; +// btSoftBody* psb = btSoftBodyHelpers::CreateFromTriMesh(getDeformableDynamicsWorld()->getWorldInfo(), &verts[0], &triangles[0], 20); +//// + btSoftBody* psb = btSoftBodyHelpers::CreateFromTetGenData(getDeformableDynamicsWorld()->getWorldInfo(), + TetraCube::getElements(), + 0, + TetraCube::getNodes(), + false, true, true); + + psb->scale(btVector3(2, 2, 2)); + psb->translate(btVector3(0, 4, 0)); + psb->getCollisionShape()->setMargin(0.1); + psb->setTotalMass(1); +// psb->scale(btVector3(5, 5, 5)); +// psb->translate(btVector3(-2.5, 4, -2.5)); +// psb->getCollisionShape()->setMargin(0.1); +// psb->setTotalMass(1); + psb->setSpringStiffness(2); + psb->setDampingCoefficient(0.02); + psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects + psb->m_cfg.kCHR = 1; // collision hardness with rigid body + psb->m_cfg.kDF = 2; + psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; + getDeformableDynamicsWorld()->addSoftBody(psb); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce()); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); + // add a grippers + createGrip(); + } + m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); +} + +void Pinch::exitPhysics() +{ + //cleanup in the reverse order of creation/initialization + + //remove the rigidbodies from the dynamics world and delete them + int i; + for (i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--) + { + btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i]; + btRigidBody* body = btRigidBody::upcast(obj); + if (body && body->getMotionState()) + { + delete body->getMotionState(); + } + m_dynamicsWorld->removeCollisionObject(obj); + delete obj; + } + + //delete collision shapes + for (int j = 0; j < m_collisionShapes.size(); j++) + { + btCollisionShape* shape = m_collisionShapes[j]; + delete shape; + } + m_collisionShapes.clear(); + + delete m_dynamicsWorld; + + delete m_solver; + + delete m_broadphase; + + delete m_dispatcher; + + delete m_collisionConfiguration; +} + + + +class CommonExampleInterface* PinchCreateFunc(struct CommonExampleOptions& options) +{ + return new Pinch(options.m_guiHelper); +} + + diff --git a/examples/DeformableDemo/Pinch.h b/examples/DeformableDemo/Pinch.h new file mode 100644 index 000000000..3d01b262f --- /dev/null +++ b/examples/DeformableDemo/Pinch.h @@ -0,0 +1,19 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2016 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 _PINCH_H +#define _PINCH_H + +class CommonExampleInterface* PinchCreateFunc(struct CommonExampleOptions& options); + +#endif //_PINCH_H diff --git a/examples/DeformableDemo/VolumetricDeformable.cpp b/examples/DeformableDemo/VolumetricDeformable.cpp new file mode 100644 index 000000000..6f2b88f8d --- /dev/null +++ b/examples/DeformableDemo/VolumetricDeformable.cpp @@ -0,0 +1,296 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2016 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. + */ + +///create 125 (5x5x5) dynamic object +#define ARRAY_SIZE_X 5 +#define ARRAY_SIZE_Y 5 +#define ARRAY_SIZE_Z 5 + +//maximum number of objects (and allow user to shoot additional boxes) +#define MAX_PROXIES (ARRAY_SIZE_X * ARRAY_SIZE_Y * ARRAY_SIZE_Z + 1024) + +///scaling of the objects (0.1 = 20 centimeter boxes ) +#define SCALING 1. +#define START_POS_X -5 +#define START_POS_Y -5 +#define START_POS_Z -3 + +#include "VolumetricDeformable.h" +///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files. +#include "btBulletDynamicsCommon.h" +#include "BulletSoftBody/btDeformableRigidDynamicsWorld.h" +#include "BulletSoftBody/btSoftBody.h" +#include "BulletSoftBody/btSoftBodyHelpers.h" +#include "BulletSoftBody/btDeformableBodySolver.h" +#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h" +#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" +#include //printf debugging + +#include "../CommonInterfaces/CommonRigidBodyBase.h" +#include "../Utils/b3ResourcePath.h" + +///The VolumetricDeformable shows the use of rolling friction. +///Spheres will come to a rest on a sloped plane using a constraint. Damping cannot achieve the same. +///Generally it is best to leave the rolling friction coefficient zero (or close to zero). + + +struct TetraCube +{ +#include "../SoftDemo/cube.inl" +}; + +class VolumetricDeformable : public CommonRigidBodyBase +{ +public: + VolumetricDeformable(struct GUIHelperInterface* helper) + : CommonRigidBodyBase(helper) + { + } + virtual ~VolumetricDeformable() + { + } + void initPhysics(); + + void exitPhysics(); + + void resetCamera() + { + float dist = 20; + float pitch = -45; + float yaw = 100; + float targetPos[3] = {0, 3, 0}; + m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]); + } + + void stepSimulation(float deltaTime) + { + //use a smaller internal timestep, there are stability issues + float internalTimeStep = 1. / 240.f; + m_dynamicsWorld->stepSimulation(deltaTime, 4, internalTimeStep); + } + + void createStaticBox(const btVector3& halfEdge, const btVector3& translation) + { + btCollisionShape* box = new btBoxShape(halfEdge); + m_collisionShapes.push_back(box); + + btTransform Transform; + Transform.setIdentity(); + Transform.setOrigin(translation); + Transform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0.0)); + //We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here: + btScalar mass(0.); + //rigidbody is dynamic if and only if mass is non zero, otherwise static + bool isDynamic = (mass != 0.f); + btVector3 localInertia(0, 0, 0); + if (isDynamic) + box->calculateLocalInertia(mass, localInertia); + //using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects + btDefaultMotionState* myMotionState = new btDefaultMotionState(Transform); + btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, box, localInertia); + btRigidBody* body = new btRigidBody(rbInfo); + body->setFriction(0.5); + + //add the ground to the dynamics world + m_dynamicsWorld->addRigidBody(body); + } + + void Ctor_RbUpStack(int count) + { + float mass = 0.02; + + btCompoundShape* cylinderCompound = new btCompoundShape; + btCollisionShape* cylinderShape = new btCylinderShapeX(btVector3(2, .5, .5)); + btCollisionShape* boxShape = new btBoxShape(btVector3(2, .5, .5)); + btTransform localTransform; + localTransform.setIdentity(); + cylinderCompound->addChildShape(localTransform, boxShape); + btQuaternion orn(SIMD_HALF_PI, 0, 0); + localTransform.setRotation(orn); + // localTransform.setOrigin(btVector3(1,1,1)); + cylinderCompound->addChildShape(localTransform, cylinderShape); + + btCollisionShape* shape[] = { + new btBoxShape(btVector3(1, 1, 1)), + }; + static const int nshapes = sizeof(shape) / sizeof(shape[0]); + for (int i = 0; i < count; ++i) + { + btTransform startTransform; + startTransform.setIdentity(); + startTransform.setOrigin(btVector3(i, 10 + 2 * i, i-1)); + createRigidBody(mass, startTransform, shape[i % nshapes]); + } + } + + virtual const btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() const + { + ///just make it a btSoftRigidDynamicsWorld please + ///or we will add type checking + return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; + } + + virtual btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() + { + ///just make it a btSoftRigidDynamicsWorld please + ///or we will add type checking + return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; + } + + virtual void renderScene() + { + CommonRigidBodyBase::renderScene(); + btDeformableRigidDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); + + for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++) + { + btSoftBody* psb = (btSoftBody*)deformableWorld->getSoftBodyArray()[i]; + //if (softWorld->getDebugDrawer() && !(softWorld->getDebugDrawer()->getDebugMode() & (btIDebugDraw::DBG_DrawWireframe))) + { + btSoftBodyHelpers::DrawFrame(psb, deformableWorld->getDebugDrawer()); + btSoftBodyHelpers::Draw(psb, deformableWorld->getDebugDrawer(), deformableWorld->getDrawFlags()); + } + } + } +}; + +void VolumetricDeformable::initPhysics() +{ + m_guiHelper->setUpAxis(1); + + ///collision configuration contains default setup for memory, collision setup + m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration(); + + ///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(); + btDeformableBodySolver* deformableBodySolver = new btDeformableBodySolver(); + + ///the default constraint solver. For parallel processing you can use a different solver (see Extras/BulletMultiThreaded) + btMultiBodyConstraintSolver* sol = new btMultiBodyConstraintSolver(); + m_solver = sol; + + m_dynamicsWorld = new btDeformableRigidDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); + deformableBodySolver->setWorld(getDeformableDynamicsWorld()); + // m_dynamicsWorld->getSolverInfo().m_singleAxisDeformableThreshold = 0.f;//faster but lower quality + btVector3 gravity = btVector3(0, -10, 0); + m_dynamicsWorld->setGravity(gravity); + getDeformableDynamicsWorld()->getWorldInfo().m_gravity = gravity; + m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); + + { + ///create a ground + btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(150.), btScalar(50.), btScalar(150.))); + m_collisionShapes.push_back(groundShape); + + btTransform groundTransform; + groundTransform.setIdentity(); + groundTransform.setOrigin(btVector3(0, -50, 0)); + groundTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0.0)); + //We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here: + btScalar mass(0.); + //rigidbody is dynamic if and only if mass is non zero, otherwise static + bool isDynamic = (mass != 0.f); + btVector3 localInertia(0, 0, 0); + if (isDynamic) + groundShape->calculateLocalInertia(mass, localInertia); + //using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects + btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform); + btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia); + btRigidBody* body = new btRigidBody(rbInfo); + body->setFriction(0.5); + + //add the ground to the dynamics world + m_dynamicsWorld->addRigidBody(body); + } + + createStaticBox(btVector3(1, 5, 5), btVector3(-5,0,0)); + createStaticBox(btVector3(1, 5, 5), btVector3(5,0,0)); + createStaticBox(btVector3(5, 5, 1), btVector3(0,0,5)); + createStaticBox(btVector3(5, 5, 1), btVector3(0,0,-5)); + + // create volumetric soft body + { + btSoftBody* psb = btSoftBodyHelpers::CreateFromTetGenData(getDeformableDynamicsWorld()->getWorldInfo(), + TetraCube::getElements(), + 0, + TetraCube::getNodes(), + false, true, true); + getDeformableDynamicsWorld()->addSoftBody(psb); + psb->scale(btVector3(2, 2, 2)); + psb->translate(btVector3(0, 5, 0)); +// psb->setVolumeMass(10); + psb->getCollisionShape()->setMargin(0.25); +// psb->generateBendingConstraints(2); + psb->setTotalMass(1); + psb->setSpringStiffness(1); + psb->setDampingCoefficient(0.01); + psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects + psb->m_cfg.kCHR = 1; // collision hardness with rigid body + psb->m_cfg.kDF = 0.5; + psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; + getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce()); + getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); + } + // add a few rigid bodies + Ctor_RbUpStack(4); + + m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); +} + +void VolumetricDeformable::exitPhysics() +{ + //cleanup in the reverse order of creation/initialization + + //remove the rigidbodies from the dynamics world and delete them + int i; + for (i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--) + { + btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i]; + btRigidBody* body = btRigidBody::upcast(obj); + if (body && body->getMotionState()) + { + delete body->getMotionState(); + } + m_dynamicsWorld->removeCollisionObject(obj); + delete obj; + } + + //delete collision shapes + for (int j = 0; j < m_collisionShapes.size(); j++) + { + btCollisionShape* shape = m_collisionShapes[j]; + delete shape; + } + m_collisionShapes.clear(); + + delete m_dynamicsWorld; + + delete m_solver; + + delete m_broadphase; + + delete m_dispatcher; + + delete m_collisionConfiguration; +} + + + +class CommonExampleInterface* VolumetricDeformableCreateFunc(struct CommonExampleOptions& options) +{ + return new VolumetricDeformable(options.m_guiHelper); +} + + diff --git a/examples/DeformableDemo/VolumetricDeformable.h b/examples/DeformableDemo/VolumetricDeformable.h new file mode 100644 index 000000000..04e30d9c6 --- /dev/null +++ b/examples/DeformableDemo/VolumetricDeformable.h @@ -0,0 +1,19 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2016 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 _VOLUMETRIC_DEFORMABLE_H +#define _VOLUMETRIC_DEFORMABLE_H + +class CommonExampleInterface* VolumetricDeformableCreateFunc(struct CommonExampleOptions& options); + +#endif //_VOLUMETRIC_DEFORMABLE__H diff --git a/examples/ExampleBrowser/CMakeLists.txt b/examples/ExampleBrowser/CMakeLists.txt index cfae5fcc5..19334b2db 100644 --- a/examples/ExampleBrowser/CMakeLists.txt +++ b/examples/ExampleBrowser/CMakeLists.txt @@ -359,14 +359,14 @@ SET(BulletExampleBrowser_SRCS ../MultiBody/MultiBodyConstraintFeedback.cpp ../SoftDemo/SoftDemo.cpp ../SoftDemo/SoftDemo.h - ../Pinch/Pinch.cpp - ../Pinch/Pinch.h - ../DeformableContact/DeformableContact.cpp - ../DeformableContact/DeformableContact.h - ../DeformableDemo/DeformableDemo.cpp - ../DeformableDemo/DeformableDemo.h - ../VolumetricDeformable/VolumetricDeformable.cpp - ../VolumetricDeformable/VolumetricDeformable.h + ../DeformableDemo/Pinch.cpp + ../DeformableDemo/Pinch.h + ../DeformableDemo/DeformableMultibody.cpp + ../DeformableDemo/DeformableMultibody.h + ../DeformableDemo/DeformableRigid.cpp + ../DeformableDemo/DeformableRigid.h + ../DeformableDemo/VolumetricDeformable.cpp + ../DeformableDemo/VolumetricDeformable.h ../MultiBody/MultiDofDemo.cpp ../MultiBody/MultiDofDemo.h ../RigidBody/RigidBodySoftContact.cpp diff --git a/examples/ExampleBrowser/ExampleEntries.cpp b/examples/ExampleBrowser/ExampleEntries.cpp index f186f642a..481d36c5d 100644 --- a/examples/ExampleBrowser/ExampleEntries.cpp +++ b/examples/ExampleBrowser/ExampleEntries.cpp @@ -47,11 +47,10 @@ #include "../FractureDemo/FractureDemo.h" #include "../DynamicControlDemo/MotorDemo.h" #include "../RollingFrictionDemo/RollingFrictionDemo.h" -#include "../DeformableDemo/DeformableDemo.h" -#include "../Pinch/Pinch.h" -#include "../DeformableContact/DeformableContact.h" -#include "../MultiBodyBaseline/MultiBodyBaseline.h" -#include "../VolumetricDeformable/VolumetricDeformable.h" +#include "../DeformableDemo/DeformableRigid.h" +#include "../DeformableDemo/Pinch.h" +#include "../DeformableDemo/DeformableMultibody.h" +#include "../DeformableDemo/VolumetricDeformable.h" #include "../SharedMemory/PhysicsServerExampleBullet2.h" #include "../SharedMemory/PhysicsServerExample.h" #include "../SharedMemory/PhysicsClientExample.h" @@ -196,10 +195,10 @@ static ExampleEntry gDefaultExamples[] = //ExampleEntry(1, "Spheres & Plane C-API (Bullet3)", "Collision C-API using Bullet 3.x backend", CollisionTutorialBullet2CreateFunc,TUT_SPHERE_PLANE_RTB3), ExampleEntry(0, "Deformabe Body"), - ExampleEntry(1, "Deformable-RigidBody Contact", "Deformable test", DeformableCreateFunc), + ExampleEntry(1, "Deformable-RigidBody Contact", "Deformable test", DeformableRigidCreateFunc), ExampleEntry(1, "Grasp Deformable Cube", "Grasping test", PinchCreateFunc), ExampleEntry(1, "Volumetric Deformable Objects", "Volumetric Deformable test", VolumetricDeformableCreateFunc), - ExampleEntry(1, "Deformable-MultiBody Contact", "MultiBody and Deformable contact", DeformableContactCreateFunc), + ExampleEntry(1, "Deformable-MultiBody Contact", "MultiBody and Deformable contact", DeformableMultibodyCreateFunc), // ExampleEntry(1, "MultiBody Baseline", "MultiBody Baseline", MultiBodyBaselineCreateFunc), #ifdef INCLUDE_CLOTH_DEMOS diff --git a/examples/ExampleBrowser/premake4.lua b/examples/ExampleBrowser/premake4.lua index ff81b34b7..985a0457b 100644 --- a/examples/ExampleBrowser/premake4.lua +++ b/examples/ExampleBrowser/premake4.lua @@ -189,9 +189,6 @@ project "App_BulletExampleBrowser" "../VoronoiFracture/*", "../SoftDemo/*", "../DeformableDemo/*", - "../DeformableContact/*", - "../VolumetricDeformable/*", - "../Pinch/*", "../RollingFrictionDemo/*", "../rbdl/*", "../FractureDemo/*", diff --git a/examples/Pinch/Pinch.cpp b/examples/Pinch/Pinch.cpp deleted file mode 100644 index c6e26ddb1..000000000 --- a/examples/Pinch/Pinch.cpp +++ /dev/null @@ -1,399 +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. -*/ - -///create 125 (5x5x5) dynamic object -#define ARRAY_SIZE_X 5 -#define ARRAY_SIZE_Y 5 -#define ARRAY_SIZE_Z 5 - -//maximum number of objects (and allow user to shoot additional boxes) -#define MAX_PROXIES (ARRAY_SIZE_X * ARRAY_SIZE_Y * ARRAY_SIZE_Z + 1024) - -///scaling of the objects (0.1 = 20 centimeter boxes ) -#define SCALING 1. -#define START_POS_X -5 -#define START_POS_Y -5 -#define START_POS_Z -3 - -#include "Pinch.h" -///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files. -#include "btBulletDynamicsCommon.h" -#include "BulletSoftBody/btDeformableRigidDynamicsWorld.h" -#include "BulletSoftBody/btSoftBody.h" -#include "BulletSoftBody/btSoftBodyHelpers.h" -#include "BulletSoftBody/btDeformableBodySolver.h" -#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h" -#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" -#include //printf debugging - -#include "../CommonInterfaces/CommonRigidBodyBase.h" -#include "../Utils/b3ResourcePath.h" - -///The Pinch shows the use of rolling friction. -///Spheres will come to a rest on a sloped plane using a constraint. Damping cannot achieve the same. -///Generally it is best to leave the rolling friction coefficient zero (or close to zero). - -struct TetraCube -{ -#include "../SoftDemo/cube.inl" -}; - -struct TetraBunny -{ -#include "../SoftDemo/bunny.inl" -}; - - -class Pinch : public CommonRigidBodyBase -{ -public: - Pinch(struct GUIHelperInterface* helper) - : CommonRigidBodyBase(helper) - { - } - virtual ~Pinch() - { - } - void initPhysics(); - - void exitPhysics(); - - void resetCamera() - { - float dist = 25; - float pitch = -30; - float yaw = 100; - float targetPos[3] = {0, -0, 0}; - m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]); - } - - void stepSimulation(float deltaTime) - { - //use a smaller internal timestep, there are stability issues - float internalTimeStep = 1. / 240.f; - m_dynamicsWorld->stepSimulation(deltaTime, 4, internalTimeStep); - } - - void createGrip() - { - int count = 2; - float mass = 2; - btCollisionShape* shape[] = { - new btBoxShape(btVector3(3, 3, 0.5)), - }; - static const int nshapes = sizeof(shape) / sizeof(shape[0]); - for (int i = 0; i < count; ++i) - { - btTransform startTransform; - startTransform.setIdentity(); - startTransform.setOrigin(btVector3(10, 0, 0)); - startTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0.)); - createRigidBody(mass, startTransform, shape[i % nshapes]); - } - } - - virtual const btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() const - { - return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; - } - - virtual btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() - { - return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; - } - - virtual void renderScene() - { - CommonRigidBodyBase::renderScene(); - btDeformableRigidDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); - - for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++) - { - btSoftBody* psb = (btSoftBody*)deformableWorld->getSoftBodyArray()[i]; - { - btSoftBodyHelpers::DrawFrame(psb, deformableWorld->getDebugDrawer()); - btSoftBodyHelpers::Draw(psb, deformableWorld->getDebugDrawer(), deformableWorld->getDrawFlags()); - } - } - } -}; - -void dynamics(btScalar time, btDeformableRigidDynamicsWorld* world) -{ - btAlignedObjectArray& rbs = world->getNonStaticRigidBodies(); - if (rbs.size()<2) - return; - btRigidBody* rb0 = rbs[0]; - btScalar pressTime = 0.9; - btScalar liftTime = 2.5; - btScalar shiftTime = 3.5; - btScalar holdTime = 4.5*1000; - btScalar dropTime = 5.3*1000; - btTransform rbTransform; - rbTransform.setIdentity(); - btVector3 translation; - btVector3 velocity; - - btVector3 initialTranslationLeft = btVector3(0.5,3,4); - btVector3 initialTranslationRight = btVector3(0.5,3,-4); - btVector3 pinchVelocityLeft = btVector3(0,0,-2); - btVector3 pinchVelocityRight = btVector3(0,0,2); - btVector3 liftVelocity = btVector3(0,5,0); - btVector3 shiftVelocity = btVector3(0,0,5); - btVector3 holdVelocity = btVector3(0,0,0); - btVector3 openVelocityLeft = btVector3(0,0,4); - btVector3 openVelocityRight = btVector3(0,0,-4); - - if (time < pressTime) - { - velocity = pinchVelocityLeft; - translation = initialTranslationLeft + pinchVelocityLeft * time; - } - else if (time < liftTime) - { - velocity = liftVelocity; - translation = initialTranslationLeft + pinchVelocityLeft * pressTime + liftVelocity * (time - pressTime); - - } - else if (time < shiftTime) - { - velocity = shiftVelocity; - translation = initialTranslationLeft + pinchVelocityLeft * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (time - liftTime); - } - else if (time < holdTime) - { - velocity = btVector3(0,0,0); - translation = initialTranslationLeft + pinchVelocityLeft * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (shiftTime - liftTime) + holdVelocity * (time - shiftTime); - } - else if (time < dropTime) - { - velocity = openVelocityLeft; - translation = initialTranslationLeft + pinchVelocityLeft * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (shiftTime - liftTime) + holdVelocity * (holdTime - shiftTime)+ openVelocityLeft * (time - holdTime); - } - else - { - velocity = holdVelocity; - translation = initialTranslationLeft + pinchVelocityLeft * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (shiftTime - liftTime) + holdVelocity * (holdTime - shiftTime)+ openVelocityLeft * (dropTime - holdTime); - } - rbTransform.setOrigin(translation); - rbTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0)); - rb0->setCenterOfMassTransform(rbTransform); - rb0->setAngularVelocity(btVector3(0,0,0)); - rb0->setLinearVelocity(velocity); - - btRigidBody* rb1 = rbs[1]; - if (time < pressTime) - { - velocity = pinchVelocityRight; - translation = initialTranslationRight + pinchVelocityRight * time; - } - else if (time < liftTime) - { - velocity = liftVelocity; - translation = initialTranslationRight + pinchVelocityRight * pressTime + liftVelocity * (time - pressTime); - - } - else if (time < shiftTime) - { - velocity = shiftVelocity; - translation = initialTranslationRight + pinchVelocityRight * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (time - liftTime); - } - else if (time < holdTime) - { - velocity = btVector3(0,0,0); - translation = initialTranslationRight + pinchVelocityRight * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (shiftTime - liftTime) + holdVelocity * (time - shiftTime); - } - else if (time < dropTime) - { - velocity = openVelocityRight; - translation = initialTranslationRight + pinchVelocityRight * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (shiftTime - liftTime) + holdVelocity * (holdTime - shiftTime)+ openVelocityRight * (time - holdTime); - } - else - { - velocity = holdVelocity; - translation = initialTranslationRight + pinchVelocityRight * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (shiftTime - liftTime) + holdVelocity * (holdTime - shiftTime)+ openVelocityRight * (dropTime - holdTime); - } - rbTransform.setOrigin(translation); - rbTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0)); - rb1->setCenterOfMassTransform(rbTransform); - rb1->setAngularVelocity(btVector3(0,0,0)); - rb1->setLinearVelocity(velocity); - - rb0->setFriction(20); - rb1->setFriction(20); -} - -void Pinch::initPhysics() -{ - m_guiHelper->setUpAxis(1); - - m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration(); - - m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration); - - m_broadphase = new btDbvtBroadphase(); - btDeformableBodySolver* deformableBodySolver = new btDeformableBodySolver(); - - btMultiBodyConstraintSolver* sol = new btMultiBodyConstraintSolver(); - m_solver = sol; - - m_dynamicsWorld = new btDeformableRigidDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); - deformableBodySolver->setWorld(getDeformableDynamicsWorld()); - // m_dynamicsWorld->getSolverInfo().m_singleAxisDeformableThreshold = 0.f;//faster but lower quality - btVector3 gravity = btVector3(0, -10, 0); - m_dynamicsWorld->setGravity(gravity); - getDeformableDynamicsWorld()->getWorldInfo().m_gravity = gravity; - - getDeformableDynamicsWorld()->setSolverCallback(dynamics); - m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); - - //create a ground - { - btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(150.), btScalar(25.), btScalar(150.))); - - m_collisionShapes.push_back(groundShape); - - btTransform groundTransform; - groundTransform.setIdentity(); - groundTransform.setOrigin(btVector3(0, -25, 0)); - groundTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0)); - //We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here: - btScalar mass(0.); - - //rigidbody is dynamic if and only if mass is non zero, otherwise static - bool isDynamic = (mass != 0.f); - - btVector3 localInertia(0, 0, 0); - if (isDynamic) - groundShape->calculateLocalInertia(mass, localInertia); - - //using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects - btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform); - btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia); - btRigidBody* body = new btRigidBody(rbInfo); - body->setFriction(0.5); - - //add the ground to the dynamics world - m_dynamicsWorld->addRigidBody(body); - } - - // create a soft block - { - btScalar verts[24] = {0.f, 0.f, 0.f, - 1.f, 0.f, 0.f, - 0.f, 1.f, 0.f, - 0.f, 0.f, 1.f, - 1.f, 1.f, 0.f, - 0.f, 1.f, 1.f, - 1.f, 0.f, 1.f, - 1.f, 1.f, 1.f - }; - int triangles[60] = {0, 6, 3, - 0,1,6, - 7,5,3, - 7,3,6, - 4,7,6, - 4,6,1, - 7,2,5, - 7,4,2, - 0,3,2, - 2,3,5, - 0,2,4, - 0,4,1, - 0,6,5, - 0,6,4, - 3,4,2, - 3,4,7, - 2,7,3, - 2,7,1, - 4,5,0, - 4,5,6, - }; -// btSoftBody* psb = btSoftBodyHelpers::CreateFromTriMesh(getDeformableDynamicsWorld()->getWorldInfo(), &verts[0], &triangles[0], 20); -//// - btSoftBody* psb = btSoftBodyHelpers::CreateFromTetGenData(getDeformableDynamicsWorld()->getWorldInfo(), - TetraCube::getElements(), - 0, - TetraCube::getNodes(), - false, true, true); - - psb->scale(btVector3(2, 2, 2)); - psb->translate(btVector3(0, 4, 0)); - psb->getCollisionShape()->setMargin(0.1); - psb->setTotalMass(1); -// psb->scale(btVector3(5, 5, 5)); -// psb->translate(btVector3(-2.5, 4, -2.5)); -// psb->getCollisionShape()->setMargin(0.1); -// psb->setTotalMass(1); - psb->setSpringStiffness(2); - psb->setDampingCoefficient(0.02); - psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects - psb->m_cfg.kCHR = 1; // collision hardness with rigid body - psb->m_cfg.kDF = 2; - psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; - getDeformableDynamicsWorld()->addSoftBody(psb); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce()); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); - // add a grippers - createGrip(); - } - m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); -} - -void Pinch::exitPhysics() -{ - //cleanup in the reverse order of creation/initialization - - //remove the rigidbodies from the dynamics world and delete them - int i; - for (i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--) - { - btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i]; - btRigidBody* body = btRigidBody::upcast(obj); - if (body && body->getMotionState()) - { - delete body->getMotionState(); - } - m_dynamicsWorld->removeCollisionObject(obj); - delete obj; - } - - //delete collision shapes - for (int j = 0; j < m_collisionShapes.size(); j++) - { - btCollisionShape* shape = m_collisionShapes[j]; - delete shape; - } - m_collisionShapes.clear(); - - delete m_dynamicsWorld; - - delete m_solver; - - delete m_broadphase; - - delete m_dispatcher; - - delete m_collisionConfiguration; -} - - - -class CommonExampleInterface* PinchCreateFunc(struct CommonExampleOptions& options) -{ - return new Pinch(options.m_guiHelper); -} - - diff --git a/examples/Pinch/Pinch.h b/examples/Pinch/Pinch.h deleted file mode 100644 index 6c7e2fb3c..000000000 --- a/examples/Pinch/Pinch.h +++ /dev/null @@ -1,20 +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 _PINCH_H -#define _PINCH_H - -class CommonExampleInterface* PinchCreateFunc(struct CommonExampleOptions& options); - -#endif //_PINCH_H diff --git a/examples/VolumetricDeformable/VolumetricDeformable.cpp b/examples/VolumetricDeformable/VolumetricDeformable.cpp deleted file mode 100644 index b30e4ac4d..000000000 --- a/examples/VolumetricDeformable/VolumetricDeformable.cpp +++ /dev/null @@ -1,298 +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. -*/ - -///create 125 (5x5x5) dynamic object -#define ARRAY_SIZE_X 5 -#define ARRAY_SIZE_Y 5 -#define ARRAY_SIZE_Z 5 - -//maximum number of objects (and allow user to shoot additional boxes) -#define MAX_PROXIES (ARRAY_SIZE_X * ARRAY_SIZE_Y * ARRAY_SIZE_Z + 1024) - -///scaling of the objects (0.1 = 20 centimeter boxes ) -#define SCALING 1. -#define START_POS_X -5 -#define START_POS_Y -5 -#define START_POS_Z -3 - -#include "VolumetricDeformable.h" -///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files. -#include "btBulletDynamicsCommon.h" -#include "BulletSoftBody/btDeformableRigidDynamicsWorld.h" -#include "BulletSoftBody/btSoftBody.h" -#include "BulletSoftBody/btSoftBodyHelpers.h" -#include "BulletSoftBody/btDeformableBodySolver.h" -#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h" -#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h" -#include //printf debugging - -#include "../CommonInterfaces/CommonRigidBodyBase.h" -#include "../Utils/b3ResourcePath.h" - -///The VolumetricDeformable shows the use of rolling friction. -///Spheres will come to a rest on a sloped plane using a constraint. Damping cannot achieve the same. -///Generally it is best to leave the rolling friction coefficient zero (or close to zero). - - -struct TetraCube -{ -#include "../SoftDemo/cube.inl" -}; - -class VolumetricDeformable : public CommonRigidBodyBase -{ -public: - VolumetricDeformable(struct GUIHelperInterface* helper) - : CommonRigidBodyBase(helper) - { - } - virtual ~VolumetricDeformable() - { - } - void initPhysics(); - - void exitPhysics(); - - void resetCamera() - { - float dist = 20; - float pitch = -45; - float yaw = 100; - float targetPos[3] = {0, 3, 0}; - m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]); - } - - void stepSimulation(float deltaTime) - { - //use a smaller internal timestep, there are stability issues - float internalTimeStep = 1. / 240.f; - m_dynamicsWorld->stepSimulation(deltaTime, 4, internalTimeStep); - } - - void createStaticBox(const btVector3& halfEdge, const btVector3& translation) - { - btCollisionShape* box = new btBoxShape(halfEdge); - m_collisionShapes.push_back(box); - - btTransform Transform; - Transform.setIdentity(); - Transform.setOrigin(translation); - Transform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0.0)); - //We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here: - btScalar mass(0.); - //rigidbody is dynamic if and only if mass is non zero, otherwise static - bool isDynamic = (mass != 0.f); - btVector3 localInertia(0, 0, 0); - if (isDynamic) - box->calculateLocalInertia(mass, localInertia); - //using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects - btDefaultMotionState* myMotionState = new btDefaultMotionState(Transform); - btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, box, localInertia); - btRigidBody* body = new btRigidBody(rbInfo); - body->setFriction(0.5); - - //add the ground to the dynamics world - m_dynamicsWorld->addRigidBody(body); - } - - void Ctor_RbUpStack(int count) - { - float mass = 0.02; - - btCompoundShape* cylinderCompound = new btCompoundShape; - btCollisionShape* cylinderShape = new btCylinderShapeX(btVector3(2, .5, .5)); - btCollisionShape* boxShape = new btBoxShape(btVector3(2, .5, .5)); - btTransform localTransform; - localTransform.setIdentity(); - cylinderCompound->addChildShape(localTransform, boxShape); - btQuaternion orn(SIMD_HALF_PI, 0, 0); - localTransform.setRotation(orn); - // localTransform.setOrigin(btVector3(1,1,1)); - cylinderCompound->addChildShape(localTransform, cylinderShape); - - btCollisionShape* shape[] = { - new btBoxShape(btVector3(1, 1, 1)), - }; - static const int nshapes = sizeof(shape) / sizeof(shape[0]); - for (int i = 0; i < count; ++i) - { - btTransform startTransform; - startTransform.setIdentity(); - startTransform.setOrigin(btVector3(i, 10 + 2 * i, i-1)); - createRigidBody(mass, startTransform, shape[i % nshapes]); - } - } - - virtual const btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() const - { - ///just make it a btSoftRigidDynamicsWorld please - ///or we will add type checking - return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; - } - - virtual btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() - { - ///just make it a btSoftRigidDynamicsWorld please - ///or we will add type checking - return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld; - } - - virtual void renderScene() - { - CommonRigidBodyBase::renderScene(); - btDeformableRigidDynamicsWorld* deformableWorld = getDeformableDynamicsWorld(); - - for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++) - { - btSoftBody* psb = (btSoftBody*)deformableWorld->getSoftBodyArray()[i]; - //if (softWorld->getDebugDrawer() && !(softWorld->getDebugDrawer()->getDebugMode() & (btIDebugDraw::DBG_DrawWireframe))) - { - btSoftBodyHelpers::DrawFrame(psb, deformableWorld->getDebugDrawer()); - btSoftBodyHelpers::Draw(psb, deformableWorld->getDebugDrawer(), deformableWorld->getDrawFlags()); - } - } - } -}; - -void VolumetricDeformable::initPhysics() -{ - m_guiHelper->setUpAxis(1); - - ///collision configuration contains default setup for memory, collision setup - m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration(); - - ///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(); - btDeformableBodySolver* deformableBodySolver = new btDeformableBodySolver(); - - ///the default constraint solver. For parallel processing you can use a different solver (see Extras/BulletMultiThreaded) - btMultiBodyConstraintSolver* sol = new btMultiBodyConstraintSolver(); - m_solver = sol; - - m_dynamicsWorld = new btDeformableRigidDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver); - deformableBodySolver->setWorld(getDeformableDynamicsWorld()); - // m_dynamicsWorld->getSolverInfo().m_singleAxisDeformableThreshold = 0.f;//faster but lower quality - btVector3 gravity = btVector3(0, -10, 0); - m_dynamicsWorld->setGravity(gravity); - getDeformableDynamicsWorld()->getWorldInfo().m_gravity = gravity; - m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); - - { - ///create a ground - btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(150.), btScalar(50.), btScalar(150.))); - m_collisionShapes.push_back(groundShape); - - btTransform groundTransform; - groundTransform.setIdentity(); - groundTransform.setOrigin(btVector3(0, -50, 0)); - groundTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0.0)); - //We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here: - btScalar mass(0.); - //rigidbody is dynamic if and only if mass is non zero, otherwise static - bool isDynamic = (mass != 0.f); - btVector3 localInertia(0, 0, 0); - if (isDynamic) - groundShape->calculateLocalInertia(mass, localInertia); - //using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects - btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform); - btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia); - btRigidBody* body = new btRigidBody(rbInfo); - body->setFriction(0.5); - - //add the ground to the dynamics world - m_dynamicsWorld->addRigidBody(body); - } - - createStaticBox(btVector3(1, 5, 5), btVector3(-5,0,0)); - createStaticBox(btVector3(1, 5, 5), btVector3(5,0,0)); - createStaticBox(btVector3(5, 5, 1), btVector3(0,0,5)); - createStaticBox(btVector3(5, 5, 1), btVector3(0,0,-5)); - - // create volumetric soft body - { - btSoftBody* psb = btSoftBodyHelpers::CreateFromTetGenData(getDeformableDynamicsWorld()->getWorldInfo(), - TetraCube::getElements(), - 0, - TetraCube::getNodes(), - false, true, true); - getDeformableDynamicsWorld()->addSoftBody(psb); - psb->scale(btVector3(2, 2, 2)); - psb->translate(btVector3(0, 5, 0)); -// psb->setVolumeMass(10); - psb->getCollisionShape()->setMargin(0.25); -// psb->generateBendingConstraints(2); - psb->setTotalMass(1); - psb->setSpringStiffness(1); - psb->setDampingCoefficient(0.01); - psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects - psb->m_cfg.kCHR = 1; // collision hardness with rigid body - psb->m_cfg.kDF = 0.5; - psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD; - getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce()); - getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity)); - } - // add a few rigid bodies - Ctor_RbUpStack(4); - - m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); -} - -void VolumetricDeformable::exitPhysics() -{ - //cleanup in the reverse order of creation/initialization - - //remove the rigidbodies from the dynamics world and delete them - int i; - for (i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--) - { - btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i]; - btRigidBody* body = btRigidBody::upcast(obj); - if (body && body->getMotionState()) - { - delete body->getMotionState(); - } - m_dynamicsWorld->removeCollisionObject(obj); - delete obj; - } - - //delete collision shapes - for (int j = 0; j < m_collisionShapes.size(); j++) - { - btCollisionShape* shape = m_collisionShapes[j]; - delete shape; - } - m_collisionShapes.clear(); - - delete m_dynamicsWorld; - - delete m_solver; - - delete m_broadphase; - - delete m_dispatcher; - - delete m_collisionConfiguration; -} - - - -class CommonExampleInterface* VolumetricDeformableCreateFunc(struct CommonExampleOptions& options) -{ - return new VolumetricDeformable(options.m_guiHelper); -} - - diff --git a/examples/VolumetricDeformable/VolumetricDeformable.h b/examples/VolumetricDeformable/VolumetricDeformable.h deleted file mode 100644 index af1cc38b6..000000000 --- a/examples/VolumetricDeformable/VolumetricDeformable.h +++ /dev/null @@ -1,20 +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 _VOLUMETRIC_DEFORMABLE_H -#define _VOLUMETRIC_DEFORMABLE_H - -class CommonExampleInterface* VolumetricDeformableCreateFunc(struct CommonExampleOptions& options); - -#endif //_VOLUMETRIC_DEFORMABLE__H diff --git a/src/BulletSoftBody/btDeformableRigidDynamicsWorld.h b/src/BulletSoftBody/btDeformableRigidDynamicsWorld.h index cc4fdae05..6489d6ebc 100644 --- a/src/BulletSoftBody/btDeformableRigidDynamicsWorld.h +++ b/src/BulletSoftBody/btDeformableRigidDynamicsWorld.h @@ -1,13 +1,11 @@ /* Bullet Continuous Collision Detection and Physics Library - Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ - + Copyright (c) 2016 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. -- cgit v1.2.1