using Bullet SoftBody sample source with Irrlicht

going
Posts: 13
Joined: Thu Oct 23, 2008 3:04 am

using Bullet SoftBody sample source with Irrlicht

Post by going »

This is equal contents of Irrlicht forum http://irrlicht.sourceforge.net/phpBB2/ ... hp?t=31091

and maybe helpful for Bullet user.

This code is not optimized and maybe a bit slow, so I want to know how and where to change the sourcecode for speeding up , people who's good at using softbody maybe helpful.

Thanks!

Code: Select all

 
#include <iostream>
#include <map>
#include <vector>
#include <list>

#include <btBulletDynamicsCommon.h>
#include "BulletSoftBody/btSoftRigidDynamicsWorld.h"
#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h"
#include "BulletSoftBody/btSoftBodyHelpers.h"
#include "BulletSoftBody/btSoftBody.h"

#include "BulletCollision/CollisionDispatch/btSphereSphereCollisionAlgorithm.h"
#include "BulletCollision/NarrowPhaseCollision/btGjkEpa2.h"
#include "LinearMath/btQuickprof.h"
#include "LinearMath/btIDebugDraw.h"
#include "LinearMath/btConvexHull.h"

#include <irrlicht.h>

#pragma comment (lib, "libbulletdynamics.lib")
#pragma comment (lib, "libbulletcollision.lib")
#pragma comment (lib, "libbulletmath.lib")
#pragma comment (lib, "libbulletsoftbody.lib")
#pragma comment (lib, "Irrlicht.lib")

using namespace irr;
using namespace core;
using namespace scene;
using namespace video;
using namespace io;
using namespace gui;

// Vertices
std::map<int, btSoftBody::Node*> vertices;
// Indices
std::vector<int> indices;
// Node->int?index??????????
// Temporary placeholder for nodes
std::map<btSoftBody::Node*, int> node_map;

#define CUBE_HALF_EXTENTS 15

struct MeshData
{
    btScalar *mqo_vertices;
    int *mqo_indices;
    int indexCount, vertexCount;
};

MeshData testMesh;

int main (void)
{
    // Irrlicht???
    IrrlichtDevice *device = createDevice(EDT_OPENGL, dimension2d<s32>(640, 480), 16,
        false, true, false, 0);
    device->setWindowCaption(L"Irrlicht + Bullet : SoftBody Demo");
    IVideoDriver* driver = device->getVideoDriver();
    ISceneManager *smgr = device->getSceneManager();

    // ??????
    ICameraSceneNode *camera = smgr->addCameraSceneNodeFPS(0, 150, 500, -1, 0, 0, false);
    camera->setPosition(core::vector3df(0,400,-300));
    camera->setFarValue(10000);
    camera->setTarget(core::vector3df(0, 300, 0));

    // SoftBody????????????????????Irrlicht??

    // you shoud change this object
    IAnimatedMesh *cubeMesh = smgr->getMesh("../media/test.3ds");
    IAnimatedMeshSceneNode *cubeNode = smgr->addAnimatedMeshSceneNode(cubeMesh, 0, -1, vector3df(0, 0, 0), vector3df(0,0,0), vector3df(1,1,1), false);
    cubeNode->setMaterialFlag(video::EMF_LIGHTING, false);

    // ??????Irrlicht??
    IAnimatedMesh *planemesh = smgr->addHillPlaneMesh("myHill", dimension2d<f32>(24, 24), dimension2d<u32>(100, 100));
    ISceneNode *q3sn = smgr->addOctTreeSceneNode(planemesh);
    q3sn->setMaterialFlag(video::EMF_LIGHTING, false);

   // you should change this resource
    q3sn->setMaterialTexture(0, driver->getTexture("../media/wall.jpg"));

    // SoftBody???????
    btSoftBodyWorldInfo   m_softBodyWorldInfo;

    // ???????
    btVector3 worldAabbMin(-10000,-10000,-10000);
    btVector3 worldAabbMax(10000,10000,10000);
    // ????????????????????
    int maxProxies = 1024;
    // broadphase????SAP??
    btAxisSweep3* broadphase = new btAxisSweep3(worldAabbMin,worldAabbMax,maxProxies);
    m_softBodyWorldInfo.m_broadphase = broadphase;

    // ?????????????????????
    //    const btDefaultCollisionConfigurationInfo collisionConfigInfo;
    btDefaultCollisionConfiguration* collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration();
    btCollisionDispatcher* dispatcher = new btCollisionDispatcher(collisionConfiguration);
    m_softBodyWorldInfo.m_dispatcher = dispatcher;

    // ???????
    btSequentialImpulseConstraintSolver* solver = new btSequentialImpulseConstraintSolver;

    // Soft-Rigit???????
    btSoftRigidDynamicsWorld* dynamicsWorld = new btSoftRigidDynamicsWorld(dispatcher,broadphase,solver,collisionConfiguration);

    // ??????????
    btCollisionShape* groundShape = new btBoxShape (btVector3(2000,CUBE_HALF_EXTENTS,2000));
    // ???MotionState???
    btDefaultMotionState* groundMotionState = new btDefaultMotionState(btTransform(btQuaternion(0,0,0,1),btVector3(0,-CUBE_HALF_EXTENTS/2.0,0)));
    // ??????????
    btRigidBody::btRigidBodyConstructionInfo groundRigidBodyCI(0,groundMotionState,groundShape,btVector3(0,0,0));
    // ????????
    btRigidBody* groundRigidBody = new btRigidBody(groundRigidBodyCI);
    groundRigidBody->setCollisionFlags( groundRigidBody->getCollisionFlags() |  btCollisionObject::CF_CUSTOM_MATERIAL_CALLBACK );
    // ?????????????
    dynamicsWorld->addRigidBody(groundRigidBody);

    // ?????
    dynamicsWorld->setGravity(btVector3(0,-10.0,0));
    // softBodyWorldInfo???????
    m_softBodyWorldInfo.m_sparsesdf.Initialize();
    m_softBodyWorldInfo.m_gravity.setValue(0,-10.0,0);
    m_softBodyWorldInfo.air_density      =   (btScalar)1.2;
    m_softBodyWorldInfo.water_density   =   0;
    m_softBodyWorldInfo.water_offset   =   0;
    m_softBodyWorldInfo.water_normal   =   btVector3(0,0,0);

    int cMeshBuffer, j;
    IMeshBuffer *mb;
    video::S3DVertex* mb_vertices;
    u16* mb_indices;

    // getMesh??????????????
    for (cMeshBuffer=0; cMeshBuffer<cubeMesh->getMesh(0)->getMeshBufferCount(); cMeshBuffer++)
    {
        // ???????????
        mb = cubeMesh->getMesh(0)->getMeshBuffer(cMeshBuffer);

        // ??????????????????????????????????
        mb_vertices = (irr::video::S3DVertex*)mb->getVertices();
        // ??????????????????????????????????????????
        mb_indices  = mb->getIndices();
    }

    // ????????????????
    // 3ds?????.obj????Irrlicht????????Index??Vertex??????Index?????Vertex??????
    // ???????SoftBody????????????????????????Vertex????????
    // ?????????????Index??????Index???????
    std::map<int, int> index_map;
    std::map<int, int> bullet_map;
    std::map<int, S3DVertex> vertex_map;
    int count = 0;
    for (int i=0; i<mb->getIndexCount(); i++)
    {
        int iIndex = mb_indices[i];
        vector3df iVertex = mb_vertices[iIndex].Pos;
        bool isFirst = true;
        for (int j=0; j<i; j++)
        {
            int jIndex = mb_indices[j];
            vector3df jVertex = mb_vertices[jIndex].Pos;
            if (iVertex == jVertex)
            {
                index_map.insert(std::make_pair(i, j));
                isFirst = false;
                break;
            }
        }
        // ???????Bullet??Index??????
        if (isFirst)
        {
            // Irrlicht?Index??????Index
            index_map.insert(std::make_pair(i, i));
            // ?????Index????Index
            bullet_map.insert(std::make_pair(i, count));
            // ??Index?????????
            vertex_map.insert(std::make_pair(count, mb_vertices[iIndex]));
            count++;
        }
    }

    // Irrlicht?Bullet???????Index-Vertex?????
    testMesh.indexCount = mb->getIndexCount();
    testMesh.mqo_indices = new int[testMesh.indexCount];
    testMesh.vertexCount = vertex_map.size();
    testMesh.mqo_vertices = new btScalar[testMesh.vertexCount*3];

    std::cout << "IndexCount=" << testMesh.indexCount << ", VertexCount=" << testMesh.vertexCount << std::endl;
    // ?????????????????????
    for (j=0; j<mb->getIndexCount(); j++)
    {
        // ?????Index???????????Index
        int index1 = index_map.find(j)->second;
        // ?????????Index?????????Index
        int index2 = bullet_map.find(index1)->second;
        testMesh.mqo_indices[j]   = index2;
    }
    // SoftBody???????????????
    for (j=0; j<testMesh.vertexCount; j++)
    {
        testMesh.mqo_vertices[3*j] =   vertex_map[j].Pos.X;
        testMesh.mqo_vertices[3*j+1] = vertex_map[j].Pos.Y;
        testMesh.mqo_vertices[3*j+2] = -vertex_map[j].Pos.Z;
    }

    std::cout << "create softbody" << std::endl;
    // ????????SoftBody????btSoftBodyHelpers????
    btSoftBody* cubeSoftBody = btSoftBodyHelpers::CreateFromTriMesh(
        m_softBodyWorldInfo, testMesh.mqo_vertices, testMesh.mqo_indices, testMesh.indexCount/3);

    std::cout << "create map" << std::endl;
    // ?????SoftBody??????????????????node->index?
    for (int i=0; i<cubeSoftBody->m_faces.size(); i++)
    {
        btSoftBody::Face face = cubeSoftBody->m_faces[i];

        for (int j=0; j<3; j++)
        {
            if (node_map.find(face.m_n[j]) == node_map.end())
            {
                node_map.insert(std::make_pair(face.m_n[j], node_map.size()));
            }
        }

        for (int j=0; j<3; j++)
        {
            // Bullet???????
            indices.push_back(node_map.find(face.m_n[j])->second);
        }
    }
    // Reverse node->index to index->node (should be unique on both sides)
    std::map<btSoftBody::Node*, int>::const_iterator node_iter;
    for (node_iter = node_map.begin(); node_iter != node_map.end(); ++node_iter)
    {
        // Bullet???
        vertices.insert(std::make_pair(node_iter->second, node_iter->first));
    }

    // Irrlicht?Vertex?Bullet?Vertex???????????
    std::cout << "update Irrlicht vertices" << std::endl;
    // ???????????
    std::map<int, int> testMesh_map;
    // SoftBody?Index?Vertex??????
    std::map<int, btSoftBody::Node*>::const_iterator it;

    // ??????????
    for (int i=0; i<mb->getVertexCount(); i++)
    {
        for (it=vertices.begin(); it != vertices.end(); ++it)
        {
            // ???????Irrlicht??????Bullet??????????
            int v_index = it->first;
            btSoftBody::Node* node = it->second;
            if (node->m_x.x() ==  mb_vertices[i].Pos.X &&
                node->m_x.y() ==  mb_vertices[i].Pos.Y &&
                node->m_x.z() == -mb_vertices[i].Pos.Z)
            {
                // Irrlicht?Bullet???????
                testMesh_map.insert(std::make_pair(i, v_index));
                break;
            }
        }
    }

    // SoftBody????????
    std::cout << "addSoftBody" << std::endl;
    cubeSoftBody->m_cfg.kDP = 0.0;// Damping coefficient [0,1]
    cubeSoftBody->m_cfg.kDF = 0.2;// Dynamic friction coefficient [0,1]
    cubeSoftBody->m_cfg.kMT = 0.02;// Pose matching coefficient [0,1]
    cubeSoftBody->m_cfg.kCHR = 1.0;// Rigid contacts hardness [0,1]
    cubeSoftBody->m_cfg.kKHR = 0.8;// Kinetic contacts hardness [0,1]
    cubeSoftBody->m_cfg.kSHR = 1.0;// Soft contacts hardness [0,1]
    cubeSoftBody->m_cfg.piterations=2;
    cubeSoftBody->m_materials[0]->m_kLST = 0.8;
    cubeSoftBody->m_materials[0]->m_kAST = 0.8;
    cubeSoftBody->m_materials[0]->m_kVST = 0.8;
    cubeSoftBody->scale(btVector3(10,10,10));
    cubeSoftBody->setPose(true, true);
    cubeSoftBody->generateBendingConstraints(2);
    cubeSoftBody->randomizeConstraints();

    // ???????Bullet??SoftBody???
    btMatrix3x3 m;
    m.setIdentity();
    cubeSoftBody->transform(btTransform(m,btVector3(0, 400, 0)));
    dynamicsWorld->addSoftBody(cubeSoftBody);

    std::cout << "start simulation" << std::endl;
    // ????????????
    while(device->run())
    {
        // ????????????????60Hz
        dynamicsWorld->stepSimulation(1/60.0f, 1);

        // Irrlicht????????
        for (int i=0; i<mb->getVertexCount(); i++)
        {
            // Irrlict??????Bullet?????
            int index = testMesh_map.find(i)->second;
            // Bullet??????????????,???????
            btSoftBody::Node* node = vertices.find(index)->second;
            // Irrlicht??mb_vertices[i]?OK
            mb_vertices[i].Pos.X = node->m_x.x();
            mb_vertices[i].Pos.Y = node->m_x.y();
            mb_vertices[i].Pos.Z = -node->m_x.z();
        }

        if (GetAsyncKeyState(VK_SPACE))
        {
            // 0????????????
            cubeSoftBody->addForce(btVector3(0, 10, 0), 0);
        }
        else if (GetAsyncKeyState(VK_ESCAPE))
        {
            break;
        }

        driver->beginScene(true, true, SColor(0,200,200,200));
        smgr->drawAll();
        driver->endScene();
    }
    device->drop();

    /* Clean up   */
    for(int i=dynamicsWorld->getNumCollisionObjects()-1;i>0;i--)
    {
        btCollisionObject*   obj=dynamicsWorld->getCollisionObjectArray()[i];
        btRigidBody*      body=btRigidBody::upcast(obj);
        if(body&&body->getMotionState())
        {
            delete body->getMotionState();
        }
        while(dynamicsWorld->getNumConstraints())
        {
            btTypedConstraint*   pc=dynamicsWorld->getConstraint(0);
            dynamicsWorld->removeConstraint(pc);
            delete pc;
        }
        btSoftBody* softBody = btSoftBody::upcast(obj);
        if (softBody)
        {
            dynamicsWorld->removeSoftBody(softBody);
        } else
        {
            dynamicsWorld->removeCollisionObject(obj);
        }
        delete obj;
    }

    delete [] testMesh.mqo_indices;
    delete [] testMesh.mqo_vertices;

    // ???????????????????
    delete dynamicsWorld;
    delete solver;
    delete collisionConfiguration;
    delete dispatcher;
    delete broadphase;

    return 0;
} 
User avatar
Erwin Coumans
Site Admin
Posts: 4221
Joined: Sun Jun 26, 2005 6:43 pm
Location: California, USA

Re: using Bullet SoftBody sample source with Irrlicht

Post by Erwin Coumans »

Using an stl map and performing a search for each vertex is likely slow.

In Blender 3D modeler, which uses Bullet soft body simulation, each vertex stores the soft body index. Alternatively, just use an index array instead of an stl map. Here is the implementation in Blender:

Code: Select all

				int index = 0;
				for(i=it.startvertex; i<it.endvertex; i++,index++) {
					RAS_TexVert& v = it.vertex[i];
					btAssert(v.getSoftBodyIndex() >= 0);

					MT_Point3 pt (
						nodes[v.getSoftBodyIndex()].m_x.getX(),
						nodes[v.getSoftBodyIndex()].m_x.getY(),
						nodes[v.getSoftBodyIndex()].m_x.getZ());
					v.SetXYZ(pt);

					MT_Vector3 normal (
						nodes[v.getSoftBodyIndex()].m_n.getX(),
						nodes[v.getSoftBodyIndex()].m_n.getY(),
						nodes[v.getSoftBodyIndex()].m_n.getZ());
					v.SetNormal(normal);
				}
			}
Hope this helps,
Erwin
going
Posts: 13
Joined: Thu Oct 23, 2008 3:04 am

Re: using Bullet SoftBody sample source with Irrlicht

Post by going »

Thanks!

I'll try it and inform it to the people who made this sourcecode.

Thank you
going
Posts: 13
Joined: Thu Oct 23, 2008 3:04 am

Re: using Bullet SoftBody sample source with Irrlicht

Post by going »

I have one question

I am now going to read blender sources to understand bullet implementation.

What sourcecode I shoud read to understand above code and bullet related?

Thanks..
going
Posts: 13
Joined: Thu Oct 23, 2008 3:04 am

Re: using Bullet SoftBody sample source with Irrlicht

Post by going »

this is a changed ver. http://sssiii.seesaa.net/article/109806769.html

You can use it if the 3d data type is .3ds or .obj. Another file have not tested yet.

changed some coding phrase but may have some not optimized part, so If you find it, please teach me.

And I think addSoftBody function can't work if the mesh data is too big. maybe index and vertex size is limited.. so, I want to know how size is it?

Thanks

Code: Select all


#include <iostream>
#include <map>
#include <vector>
#include <list>

#include <btBulletDynamicsCommon.h>
#include "BulletSoftBody/btSoftRigidDynamicsWorld.h"
#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h"
#include "BulletSoftBody/btSoftBodyHelpers.h"
#include "BulletSoftBody/btSoftBody.h"

#include "BulletCollision/CollisionDispatch/btSphereSphereCollisionAlgorithm.h"
#include "BulletCollision/NarrowPhaseCollision/btGjkEpa2.h"
#include "LinearMath/btQuickprof.h"
#include "LinearMath/btIDebugDraw.h"
#include "LinearMath/btConvexHull.h"

#include <irrlicht.h>

#pragma comment (lib, "libbulletdynamics.lib")
#pragma comment (lib, "libbulletcollision.lib")
#pragma comment (lib, "libbulletmath.lib")
#pragma comment (lib, "libbulletsoftbody.lib")
#pragma comment (lib, "Irrlicht.lib")

using namespace irr;
using namespace core;
using namespace scene;
using namespace video;
using namespace io;
using namespace gui;

#define CUBE_HALF_EXTENTS 15

struct MeshData
{
    u16              *irr_indices;
    S3DVertex        *irr_vertices;
    int              *temp_indices;
    btScalar         *temp_vertices;
    int              *soft_indices;
    btSoftBody::Node **soft_nodes;
    int indexCount;
    int irr_vertexCount;
    int temp_vertexCount;
    int soft_nodeCount;
};

int main (void)
{
    // Irrlicht???
    IrrlichtDevice *device = createDevice(EDT_OPENGL, dimension2d<s32>(640, 480), 16,
        false, true, false, 0);
    device->setWindowCaption(L"Irrlicht + Bullet : SoftBody Demo");
    IVideoDriver* driver = device->getVideoDriver();
    ISceneManager *smgr = device->getSceneManager();

    // ??????
    ICameraSceneNode *camera = smgr->addCameraSceneNodeFPS(0, 150, 500, -1, 0, 0, false);
    camera->setPosition(core::vector3df(0,400,-300));
    camera->setFarValue(10000);
    camera->setTarget(core::vector3df(0, 300, 0));

    // SoftBody????????????????????Irrlicht??
    IAnimatedMesh *cubeMesh = smgr->getMesh("../media/earth.obj");
    IAnimatedMeshSceneNode *cubeNode = smgr->addAnimatedMeshSceneNode(cubeMesh, 0, -1, vector3df(0, 0, 0), vector3df(0,0,0), vector3df(1,1,1), false);
    cubeNode->setMaterialFlag(video::EMF_LIGHTING, false);

    // ??????Irrlicht??
    IAnimatedMesh *planemesh = smgr->addHillPlaneMesh("myHill", dimension2d<f32>(24, 24), dimension2d<u32>(100, 100));
    ISceneNode *q3sn = smgr->addOctTreeSceneNode(planemesh);
    q3sn->setMaterialFlag(video::EMF_LIGHTING, false);
    q3sn->setMaterialTexture(0, driver->getTexture("../media/wall.jpg"));

    // SoftBody???????
    btSoftBody::btSoftBodyWorldInfo	m_softBodyWorldInfo;

    // ???????
    btVector3 worldAabbMin(-10000,-10000,-10000);
    btVector3 worldAabbMax(10000,10000,10000);
    // ????????????????????
    int maxProxies = 1024;
    // broadphase????SAP??
    btAxisSweep3* broadphase = new btAxisSweep3(worldAabbMin,worldAabbMax,maxProxies);
    m_softBodyWorldInfo.m_broadphase = broadphase;

    // ?????????????????????
    btDefaultCollisionConfiguration* collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration();
    btCollisionDispatcher* dispatcher = new btCollisionDispatcher(collisionConfiguration);
    m_softBodyWorldInfo.m_dispatcher = dispatcher;

    // ???????
    btSequentialImpulseConstraintSolver* solver = new btSequentialImpulseConstraintSolver;

    // Soft-Rigit???????
    btSoftRigidDynamicsWorld* dynamicsWorld = new btSoftRigidDynamicsWorld(dispatcher,broadphase,solver,collisionConfiguration);

    // ??????????
    btCollisionShape* groundShape = new btBoxShape (btVector3(2000,CUBE_HALF_EXTENTS,2000));
    // ???MotionState???
    btDefaultMotionState* groundMotionState = new btDefaultMotionState(btTransform(btQuaternion(0,0,0,1),btVector3(0,-CUBE_HALF_EXTENTS/2.0,0)));
    // ??????????
    btRigidBody::btRigidBodyConstructionInfo groundRigidBodyCI(0,groundMotionState,groundShape,btVector3(0,0,0));
    // ????????
    btRigidBody* groundRigidBody = new btRigidBody(groundRigidBodyCI);
    groundRigidBody->setCollisionFlags( groundRigidBody->getCollisionFlags() |  btCollisionObject::CF_CUSTOM_MATERIAL_CALLBACK );
    // ?????????????
    dynamicsWorld->addRigidBody(groundRigidBody);

    // ?????
    dynamicsWorld->setGravity(btVector3(0,-10.0,0));
    // softBodyWorldInfo???????
    m_softBodyWorldInfo.m_sparsesdf.Initialize();
    m_softBodyWorldInfo.m_gravity.setValue(0,-10.0,0);
    m_softBodyWorldInfo.air_density		=	(btScalar)1.2;
    m_softBodyWorldInfo.water_density	=	0;
    m_softBodyWorldInfo.water_offset	=	0;
    m_softBodyWorldInfo.water_normal	=	btVector3(0,0,0);

    // MeshData struct
    MeshData testMesh;

    int cMeshBuffer, j;
    // MeshBuffer
    IMeshBuffer *mb;

    std::cout << "get Mesh Buffer" << std::endl;
    // getMesh??????????????
    for (cMeshBuffer=0; cMeshBuffer<cubeMesh->getMesh(0)->getMeshBufferCount(); cMeshBuffer++) 
    {
        // ???????????
        mb = cubeMesh->getMesh(0)->getMeshBuffer(cMeshBuffer); 

        // ??????????????????????????????????
        testMesh.irr_vertices = (irr::video::S3DVertex*)mb->getVertices();
        testMesh.irr_vertexCount = mb->getVertexCount();
        // ??????????????????????????????????????????
        testMesh.irr_indices  = mb->getIndices(); 
        testMesh.indexCount = mb->getIndexCount();
    } 

    // ????????????????
    // 3ds?????.obj????Irrlicht????????Index??Vertex??????Index?????Vertex??????
    // ???????SoftBody????????????????????????Vertex????????
    // ?????????????Index??????Index???????
    std::map<int, int> index_map;
    std::map<int, int> index2_map;
    std::map<int, S3DVertex> vertex_map;
    int count = 0;
    for (int i=0; i<testMesh.irr_vertexCount; i++)
    {
        int iIndex = testMesh.irr_indices[i];
        vector3df iVertex = testMesh.irr_vertices[iIndex].Pos;
        bool isFirst = true;
        for (int j=0; j<i; j++)
        {
            int jIndex = testMesh.irr_indices[j];
            vector3df jVertex = testMesh.irr_vertices[jIndex].Pos;
            if (iVertex == jVertex)
            {
                index_map.insert(std::make_pair(i, j));
                isFirst = false;
                break;
            }
        }
        // ???????Bullet??Index??????
        if (isFirst)
        {
            // Irrlicht?Index??????Index
            index_map.insert(std::make_pair(i, i));
            // ?????Index????Index
            index2_map.insert(std::make_pair(i, count));
            // ??Index?????????
            vertex_map.insert(std::make_pair(count, testMesh.irr_vertices[iIndex]));
            count++;
        }
    }

    // Temporary index-vertex data for Softbody
    testMesh.temp_indices = new int[testMesh.indexCount];
    testMesh.temp_vertexCount = vertex_map.size();
    testMesh.temp_vertices = new btScalar[testMesh.temp_vertexCount*3];

    std::cout << "IndexCount=" << testMesh.indexCount << ", IrrVertexCount=" << testMesh.irr_vertexCount << std::endl;
    std::cout << "IndexCount=" << testMesh.indexCount << ", TempVertexCount=" << testMesh.temp_vertexCount << std::endl;
    // ?????????????????????
    for (j=0; j<testMesh.indexCount; j++) 
    {
        // ?????Index???????????Index
        int index1 = index_map.find(j)->second;
        // ?????????Index?????????Index
        int index2 = index2_map.find(index1)->second;
        testMesh.temp_indices[j]   = index2;
    }
    // SoftBody???????????????
    for (j=0; j<testMesh.temp_vertexCount; j++)
    {
        testMesh.temp_vertices[3*j]   =  vertex_map[j].Pos.X;
        testMesh.temp_vertices[3*j+1] =  vertex_map[j].Pos.Y;
        testMesh.temp_vertices[3*j+2] = -vertex_map[j].Pos.Z;
    }

    std::cout << "create softbody" << std::endl;
    // ????????SoftBody????btSoftBodyHelpers????
    btSoftBody* cubeSoftBody = btSoftBodyHelpers::CreateFromTriMesh(
        m_softBodyWorldInfo, testMesh.temp_vertices, testMesh.temp_indices, testMesh.indexCount/3);

    std::cout << "create map" << std::endl;
    std::cout << "cubeSoftBody->m_faces.size()=" << cubeSoftBody->m_faces.size() << std::endl;

    // softbody?index-node???
    testMesh.soft_indices = new int[testMesh.indexCount];
    testMesh.soft_nodeCount = cubeSoftBody->m_faces.size()*3;
    testMesh.soft_nodes = new btSoftBody::Node*[testMesh.soft_nodeCount];

    // index-node data
    count = 0;
    for (int i=0; i<cubeSoftBody->m_faces.size(); i++)
    {
        // A face has three nodes
        btSoftBody::Face face = cubeSoftBody->m_faces[i];
        for (int j=0; j<3; j++)
        {
            testMesh.soft_nodes[count++] = face.m_n[j];
        }
    }

    // Irrlicht?Vertex?Bullet?Vertex???????????
    std::cout << "create softbody indices"  << std::endl;

    // ???????Irrlicht?index?Bullet?index?????
    for (int i=0; i<testMesh.indexCount; i++)
    {
        int irr_index = testMesh.irr_indices[i];
        for (int j=0; j<testMesh.indexCount; j++)
        {
            btSoftBody::Node* node = testMesh.soft_nodes[j];
            if ((node->m_x.x() ==   testMesh.irr_vertices[irr_index].Pos.X) &&
                (node->m_x.y() ==   testMesh.irr_vertices[irr_index].Pos.Y) &&
                (node->m_x.z() ==  -testMesh.irr_vertices[irr_index].Pos.Z))
            {
                // Irrlicht?Bullet???????
                testMesh.soft_indices[i] = j;
//                std::cout << "i=" << i << ", irr_index=" << irr_index << ", soft_index=" << j << std::endl;
                break;
            }
        }
    }

    // SoftBody????????
    std::cout << "addSoftBody" << std::endl;
    cubeSoftBody->m_cfg.kDP = 0.0;// Damping coefficient [0,1]
    cubeSoftBody->m_cfg.kDF = 0.2;// Dynamic friction coefficient [0,1]
    cubeSoftBody->m_cfg.kMT = 0.02;// Pose matching coefficient [0,1]
    cubeSoftBody->m_cfg.kCHR = 1.0;// Rigid contacts hardness [0,1]
    cubeSoftBody->m_cfg.kKHR = 0.8;// Kinetic contacts hardness [0,1]
    cubeSoftBody->m_cfg.kSHR = 1.0;// Soft contacts hardness [0,1]
    cubeSoftBody->m_cfg.piterations=2;
    cubeSoftBody->m_materials[0]->m_kLST = 0.8;
    cubeSoftBody->m_materials[0]->m_kAST = 0.8;
    cubeSoftBody->m_materials[0]->m_kVST = 0.8;
    cubeSoftBody->scale(btVector3(1,1,1));
    cubeSoftBody->setPose(true, true);
    cubeSoftBody->generateBendingConstraints(2);
    cubeSoftBody->randomizeConstraints();

    // ???????Bullet??SoftBody???
    btMatrix3x3 m;
    m.setIdentity();
    cubeSoftBody->transform(btTransform(m,btVector3(0, 400, 0)));
    dynamicsWorld->addSoftBody(cubeSoftBody);

    std::cout << "start simulation" << std::endl;
    // ????????????
    while(device->run())
    {
        // ????????????????60Hz
        dynamicsWorld->stepSimulation(1/60.0f, 1);

        // Irrlicht????????
        for (int i=0; i<testMesh.indexCount; i++)
        {
            // Irrlict??????Bullet?????
            int irr_index = testMesh.irr_indices[i];
            int soft_index = testMesh.soft_indices[i];
            // Bullet??????????????,???????
            btSoftBody::Node* node = testMesh.soft_nodes[soft_index];
            // Irrlicht??mb_vertices[i]?OK
            testMesh.irr_vertices[irr_index].Pos.X =  node->m_x.x();
            testMesh.irr_vertices[irr_index].Pos.Y =  node->m_x.y();
            testMesh.irr_vertices[irr_index].Pos.Z = -node->m_x.z();
            testMesh.irr_vertices[irr_index].Normal.X =  node->m_n.x();
            testMesh.irr_vertices[irr_index].Normal.Y =  node->m_n.y();
            testMesh.irr_vertices[irr_index].Normal.Z = -node->m_n.z();
        }

        if (GetAsyncKeyState(VK_SPACE))
        {
            // 0????????????
            cubeSoftBody->addForce(btVector3(0, 10, 0), 0);
        }
        else if (GetAsyncKeyState(VK_ESCAPE)) 
        {
            break;
        }

        driver->beginScene(true, true, SColor(0,200,200,200));
        smgr->drawAll();
        driver->endScene();
    }
    device->drop();

    /* Clean up	*/ 
    for(int i=dynamicsWorld->getNumCollisionObjects()-1;i>0;i--)
    {
        btCollisionObject*	obj=dynamicsWorld->getCollisionObjectArray()[i];
        btRigidBody*		body=btRigidBody::upcast(obj);
        if(body&&body->getMotionState())
        {
            delete body->getMotionState();
        }
        while(dynamicsWorld->getNumConstraints())
        {
            btTypedConstraint*	pc=dynamicsWorld->getConstraint(0);
            dynamicsWorld->removeConstraint(pc);
            delete pc;
        }
        btSoftBody* softBody = btSoftBody::upcast(obj);
        if (softBody)
        {
            dynamicsWorld->removeSoftBody(softBody);
        } else
        {
            dynamicsWorld->removeCollisionObject(obj);
        }
        delete obj;
    }

    delete [] testMesh.temp_indices;
    delete [] testMesh.temp_vertices;
    delete [] testMesh.soft_indices;
    delete [] testMesh.soft_nodes;

    // ???????????????????
    delete dynamicsWorld;
    delete solver;
    delete collisionConfiguration;
    delete dispatcher;
    delete broadphase;

    return 0;
}