Soft body

Post Reply
rookie
Posts: 12
Joined: Mon Dec 05, 2011 8:36 pm

Soft body

Post by rookie »

Is there any properties which I can tweak so that the body appears softer that it is more like a cloth rather than a marshmallow. Code is as follows

#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>

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

// Vertices
std::map<int, btSoftBody::Node*> vertices;
// Indices
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<u32>(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
IAnimatedMesh *cubeMesh = smgr->getMesh("Shirt_test.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);
cubeNode->setMaterialTexture(0, driver->getTexture("Billabong_guys_shirt3.bmp"));

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("texture.bmp"));

// SoftBody
btSoftBodyWorldInfo m_softBodyWorldInfo;

btVector3 worldAabbMin(-10000,-10000,-10000);
btVector3 worldAabbMax(10000,10000,10000);

int maxProxies = 1024;
// broadphase
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-Rigid
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();
}


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;
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(make_pair(i, j));
isFirst = false;
break;
}
}
if (isFirst)
{
index_map.insert(make_pair(i, i));
bullet_map.insert(make_pair(i, count));
vertex_map.insert(make_pair(count, mb_vertices[iIndex]));
count++;
}
}

testMesh.indexCount = mb->getIndexCount();
testMesh.mqo_indices = new int[testMesh.indexCount];
testMesh.vertexCount = vertex_map.size();
testMesh.mqo_vertices = new btScalar[testMesh.vertexCount*3];

cout << "IndexCount=" << testMesh.indexCount << ", VertexCount=" << testMesh.vertexCount << endl;
for (j=0; j<mb->getIndexCount(); j++)
{

int index1 = index_map.find(j)->second;
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;
}

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

cout << "create map" << endl;
for (int i=0; i<cubeSoftBody->m_faces.size(); i++)
{
btSoftBody::Face face = cubeSoftBody->m_faces;
for (int j=0; j<3; j++)
{
if (node_map.find(face.m_n[j]) == node_map.end())
{
node_map.insert(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(make_pair(node_iter->second, node_iter->first));
}

cout << "update Irrlicht vertices" << 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)
{
int v_index = it->first;
btSoftBody::Node* node = it->second;
if (node->m_x.x() == -mb_vertices.Pos.X && node->m_x.y() == mb_vertices.Pos.Y && node->m_x.z() == mb_vertices.Pos.Z)
{
testMesh_map.insert(make_pair(i, v_index));
break;
}
}
}

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

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

cout << "start simulation" << endl;
while(device->run())
{
dynamicsWorld->stepSimulation(1/60.0f, 1);
for (int i=0; i<mb->getVertexCount(); i++)
{

int index = testMesh_map.find(i)->second;
btSoftBody::Node* node = vertices.find(index)->second;
mb_vertices.Pos.X = node->m_x.x();
mb_vertices.Pos.Y = node->m_x.y();
mb_vertices.Pos.Z = -node->m_x.z();
}

//if (GetAsyncKeyState(KEY_SPACE))
//{
// 0番目のノードに力を加える
// cubeSoftBody->addForce(btVector3(0, 10, 0), 0);
//}
//else if (GetAsyncKeyState(KEY_ESCAPE))
//{
// break;
//}
SEvent event;
if(event.KeyInput.Key == KEY_SPACE && event.KeyInput.PressedDown)
cubeSoftBody->addForce(btVector3(0, 10, 0), 0);
else if(event.KeyInput.Key == KEY_ESCAPE && event.KeyInput.PressedDown)
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();
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;
}

The soft body falls down due to gravity but instead of the model spreading over the ground it bounces like a marshmallow. Use your own obj file to test it out. the sample video is http://sssiii.seesaa.net/article/108784481.html. I want to spread it out rather than bounce. I am using this for hobby & hence there shouldn't be any legality issues.
Xcoder79
Posts: 42
Joined: Sun Aug 07, 2011 5:27 am

Re: Soft body

Post by Xcoder79 »

Try using SoftBody->m_cfg.kDF = 1 thats what i use for my softbody and cluster collison of 64
that eliminates the marshmellow effect
rookie
Posts: 12
Joined: Mon Dec 05, 2011 8:36 pm

Re: Soft body

Post by rookie »

I am already using m_cfg.kDF = 1 with softbody->generateClusters(64) but still it gives me the marsh mellow effect.
rookie
Posts: 12
Joined: Mon Dec 05, 2011 8:36 pm

Re: Soft body

Post by rookie »

I solved the problem of mashmellow effect by changing the piterations but now he problem is I can't apply force to a single node. When I apply force to the entire soft body it shifts sideways but when I apply force to a node it doesn't show any modifications. The code is as follows


#include <QDebug>
#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>

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

// Vertices
std::map<int, btSoftBody::Node*> vertices;
// Indices
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;

class MyEventReceiver : public IEventReceiver
{
public:
// This is the one method that we have to implement
virtual bool OnEvent(const SEvent& event)
{
// Remember whether each key is down or up
if (event.EventType == irr::EET_KEY_INPUT_EVENT)
KeyIsDown[event.KeyInput.Key] = event.KeyInput.PressedDown;

return false;
}

// This is used to check whether a key is being held down
virtual bool IsKeyDown(EKEY_CODE keyCode) const
{
return KeyIsDown[keyCode];
}

MyEventReceiver()
{
for (u32 i=0; i<KEY_KEY_CODES_COUNT; ++i)
KeyIsDown = false;
}

private:
// We use this array to store the current state of each key
bool KeyIsDown[KEY_KEY_CODES_COUNT];
};

int main (void)
{
// Irrlicht
MyEventReceiver receiver;
IrrlichtDevice *device = createDevice(EDT_OPENGL, dimension2d<u32>(640, 480), 16, false, true, false, &receiver);
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
IAnimatedMesh *cubeMesh = smgr->getMesh("Shirt_test.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);
cubeNode->setMaterialTexture(0, driver->getTexture("Billabong_guys_shirt3.bmp"));
// cubeNode->setScale(vector3df(4, 4, 4));

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("texture.bmp"));

// SoftBody
btSoftBodyWorldInfo m_softBodyWorldInfo;

btVector3 worldAabbMin(-10000,-10000,-10000);
btVector3 worldAabbMax(10000,10000,10000);

int maxProxies = 1024;
// broadphase
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-Rigid
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();
}


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;
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(make_pair(i, j));
isFirst = false;
break;
}
}
if (isFirst)
{
index_map.insert(make_pair(i, i));
bullet_map.insert(make_pair(i, count));
vertex_map.insert(make_pair(count, mb_vertices[iIndex]));
count++;
}
}

testMesh.indexCount = mb->getIndexCount();
testMesh.mqo_indices = new int[testMesh.indexCount];
testMesh.vertexCount = vertex_map.size();
testMesh.mqo_vertices = new btScalar[testMesh.vertexCount*3];

cout << "IndexCount=" << testMesh.indexCount << ", VertexCount=" << testMesh.vertexCount << endl;
for (j=0; j<mb->getIndexCount(); j++)
{

int index1 = index_map.find(j)->second;
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;
}

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

cout << "create map" << endl;
for (int i=0; i<cubeSoftBody->m_faces.size(); i++)
{
btSoftBody::Face face = cubeSoftBody->m_faces;
for (int j=0; j<3; j++)
{
if (node_map.find(face.m_n[j]) == node_map.end())
{
node_map.insert(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(make_pair(node_iter->second, node_iter->first));
}

cout << "update Irrlicht vertices" << 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)
{
int v_index = it->first;
btSoftBody::Node* node = it->second;
if (node->m_x.x() == -mb_vertices.Pos.X && node->m_x.y() == mb_vertices.Pos.Y && node->m_x.z() == mb_vertices.Pos.Z)
{
testMesh_map.insert(make_pair(i, v_index));
break;
}
}
}

// SoftBody
cout << "addSoftBody" << endl;
cubeSoftBody->m_cfg.kDP = 0.0;// Damping coefficient [0,1]
cubeSoftBody->m_cfg.kDF = /*0.2*/ 0.0;// Dynamic friction coefficient [0,1]
cubeSoftBody->m_cfg.kMT = 0.0;// Pose matching coefficient [0,1]
cubeSoftBody->m_cfg.kCHR = 0.0;// Rigid contacts hardness [0,1]
cubeSoftBody->m_cfg.kKHR = 0.0;// Kinetic contacts hardness [0,1]
cubeSoftBody->m_cfg.kSHR = 0.0;// Soft contacts hardness [0,1]
cubeSoftBody->m_cfg.collisions = btSoftBody::fCollision::SDF_RS + btSoftBody::fCollision::CL_SS + btSoftBody::fCollision::CL_SELF;
cubeSoftBody->m_cfg.piterations = 1;
cubeSoftBody->m_materials[0]->m_kLST = 0.1;
cubeSoftBody->m_materials[0]->m_kAST = 0.1;
cubeSoftBody->m_materials[0]->m_kVST = 0.1;
cubeSoftBody->scale(btVector3(10,10,10));
cubeSoftBody->setPose(true, true);
cubeSoftBody->generateBendingConstraints(2);
cubeSoftBody->randomizeConstraints();
cubeSoftBody->generateClusters(64);
// cubeSoftBody->setMass(10, 0);

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

cout << "start simulation" << endl;
while(device->run())
{
dynamicsWorld->stepSimulation(1/60.0f, 1);
for (int i=0; i<mb->getVertexCount(); i++)
{

int index = testMesh_map.find(i)->second;
btSoftBody::Node* node = vertices.find(index)->second;
mb_vertices.Pos.X = node->m_x.x();
mb_vertices.Pos.Y = node->m_x.y();
mb_vertices.Pos.Z = -node->m_x.z();
}

//if (GetAsyncKeyState(KEY_SPACE))
//{
// 0番目のノードに力を加える
// cubeSoftBody->addForce(btVector3(0, 10, 0), 0);
//}
//else if (GetAsyncKeyState(KEY_ESCAPE))
//{
// break;
//}
// SEvent event;
if(receiver.IsKeyDown(irr::KEY_SPACE)){
// qDebug() << "HI";
cubeSoftBody->addForce(btVector3(50, 0, 0), 10);
}
else if(receiver.IsKeyDown(irr::KEY_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();
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;
}


So when I use cubeSoftBody->addForce(btVector3(50, 0, 0)) the soft body shifts to the right but when I use cubeSoftBody->addForce(btVector3(50, 0, 0), 10); it doesn't show any modifications, that is it doesn't deform wrt the node no 10.
rookie
Posts: 12
Joined: Mon Dec 05, 2011 8:36 pm

Re: Soft body

Post by rookie »

I am trying to embed the code into qt...I am not able to run physics + irrlicht + qt...the soft body is not being rendered & hence i am not able to see the soft body falling down due to gravity...i think it is because of stepsimulation. the code for rendering is as follows.
void Model::drawIrrlichtScene()
{
u32 TimeStamp = m_Device->getTimer()->getTime();
u32 DeltaTime = 0;
// while(m_Device->run())
{
qDebug() << "start simulation";
m_Driver->beginScene(true, true, SColor(255,100,101,140));

DeltaTime = m_Device->getTimer()->getTime() - TimeStamp;
TimeStamp = m_Device->getTimer()->getTime();

m_dynamicsWorld->stepSimulation(DeltaTime*0.001f, 120);
for (int i=0; i<mb->getVertexCount(); i++)
{
int index = testMesh_map.find(i)->second;
btSoftBody::Node* node = vertices.find(index)->second;
mb_vertices.Pos.X = node->m_x.x();
mb_vertices.Pos.Y = node->m_x.y();
mb_vertices.Pos.Z = -node->m_x.z();
}


m_Scene->drawAll();
m_Driver->endScene();
}
}

Model is derived from QgraphicsItem...this function is called in paint function of model....
Post Reply