hook deformable world into the physics server
This commit is contained in:
@@ -1,6 +1,5 @@
|
|||||||
#ifndef GUI_HELPER_INTERFACE_H
|
#ifndef GUI_HELPER_INTERFACE_H
|
||||||
#define GUI_HELPER_INTERFACE_H
|
#define GUI_HELPER_INTERFACE_H
|
||||||
|
|
||||||
class btRigidBody;
|
class btRigidBody;
|
||||||
class btVector3;
|
class btVector3;
|
||||||
class btCollisionObject;
|
class btCollisionObject;
|
||||||
@@ -118,6 +117,8 @@ struct GUIHelperInterface
|
|||||||
|
|
||||||
//empty name stops dumping video
|
//empty name stops dumping video
|
||||||
virtual void dumpFramesToVideo(const char* mp4FileName){};
|
virtual void dumpFramesToVideo(const char* mp4FileName){};
|
||||||
|
virtual void drawDebugDrawerLines(){}
|
||||||
|
virtual void clearLines(){}
|
||||||
};
|
};
|
||||||
|
|
||||||
///the DummyGUIHelper does nothing, so we can test the examples without GUI/graphics (in 'console mode')
|
///the DummyGUIHelper does nothing, so we can test the examples without GUI/graphics (in 'console mode')
|
||||||
|
|||||||
@@ -128,7 +128,7 @@ public:
|
|||||||
|
|
||||||
//use a smaller internal timestep, there are stability issues
|
//use a smaller internal timestep, there are stability issues
|
||||||
float internalTimeStep = 1. / 250.f;
|
float internalTimeStep = 1. / 250.f;
|
||||||
m_dynamicsWorld->stepSimulation(deltaTime, 100, internalTimeStep);
|
m_dynamicsWorld->stepSimulation(deltaTime, 4, internalTimeStep);
|
||||||
}
|
}
|
||||||
|
|
||||||
void createGrip()
|
void createGrip()
|
||||||
|
|||||||
@@ -45,6 +45,10 @@ static bool UrdfFindMeshFile(
|
|||||||
{
|
{
|
||||||
*out_type = UrdfGeometry::FILE_CDF;
|
*out_type = UrdfGeometry::FILE_CDF;
|
||||||
}
|
}
|
||||||
|
else if (ext == ".vtk")
|
||||||
|
{
|
||||||
|
*out_type = UrdfGeometry::FILE_VTK;
|
||||||
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
b3Warning("%s: invalid mesh filename extension '%s'\n", error_message_prefix.c_str(), ext.c_str());
|
b3Warning("%s: invalid mesh filename extension '%s'\n", error_message_prefix.c_str(), ext.c_str());
|
||||||
|
|||||||
@@ -82,6 +82,7 @@ struct UrdfGeometry
|
|||||||
FILE_OBJ = 3,
|
FILE_OBJ = 3,
|
||||||
FILE_CDF = 4,
|
FILE_CDF = 4,
|
||||||
MEMORY_VERTICES = 5,
|
MEMORY_VERTICES = 5,
|
||||||
|
FILE_VTK = 6,
|
||||||
|
|
||||||
};
|
};
|
||||||
int m_meshFileType;
|
int m_meshFileType;
|
||||||
|
|||||||
@@ -338,6 +338,74 @@ B3_SHARED_API int b3LoadSoftBodySetStartOrientation(b3SharedMemoryCommandHandle
|
|||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
B3_SHARED_API int b3LoadSoftBodyAddCorotatedForce(b3SharedMemoryCommandHandle commandHandle, double corotatedMu, double corotatedLambda)
|
||||||
|
{
|
||||||
|
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
|
||||||
|
b3Assert(command->m_type == CMD_LOAD_SOFT_BODY);
|
||||||
|
command->m_loadSoftBodyArguments.m_corotatedMu = corotatedMu;
|
||||||
|
command->m_loadSoftBodyArguments.m_corotatedLambda = corotatedLambda;
|
||||||
|
command->m_updateFlags |= LOAD_SOFT_BODY_ADD_COROTATED_FORCE;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
B3_SHARED_API int b3LoadSoftBodyAddNeoHookeanForce(b3SharedMemoryCommandHandle commandHandle, double NeoHookeanMu, double NeoHookeanLambda)
|
||||||
|
{
|
||||||
|
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
|
||||||
|
b3Assert(command->m_type == CMD_LOAD_SOFT_BODY);
|
||||||
|
command->m_loadSoftBodyArguments.m_NeoHookeanMu = NeoHookeanMu;
|
||||||
|
command->m_loadSoftBodyArguments.m_NeoHookeanLambda = NeoHookeanLambda;
|
||||||
|
command->m_updateFlags |= LOAD_SOFT_BODY_ADD_NEOHOOKEAN_FORCE;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
B3_SHARED_API int b3LoadSoftBodyAddMassSpringForce(b3SharedMemoryCommandHandle commandHandle, double springElasticStiffness , double springDampingStiffness)
|
||||||
|
{
|
||||||
|
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
|
||||||
|
b3Assert(command->m_type == CMD_LOAD_SOFT_BODY);
|
||||||
|
command->m_loadSoftBodyArguments.m_springElasticStiffness = springElasticStiffness;
|
||||||
|
command->m_loadSoftBodyArguments.m_springDampingStiffness = springDampingStiffness;
|
||||||
|
command->m_updateFlags |= LOAD_SOFT_BODY_ADD_MASS_SPRING_FORCE;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
B3_SHARED_API int b3LoadSoftBodyAddGravityForce(b3SharedMemoryCommandHandle commandHandle, double gravityX, double gravityY, double gravityZ)
|
||||||
|
{
|
||||||
|
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
|
||||||
|
b3Assert(command->m_type == CMD_LOAD_SOFT_BODY);
|
||||||
|
command->m_loadSoftBodyArguments.m_gravity[0] = gravityX;
|
||||||
|
command->m_loadSoftBodyArguments.m_gravity[1] = gravityY;
|
||||||
|
command->m_loadSoftBodyArguments.m_gravity[2] = gravityZ;
|
||||||
|
command->m_updateFlags |= LOAD_SOFT_BODY_ADD_GRAVITY_FORCE;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
B3_SHARED_API int b3LoadSoftBodySetCollsionHardness(b3SharedMemoryCommandHandle commandHandle, double collisionHardness)
|
||||||
|
{
|
||||||
|
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
|
||||||
|
b3Assert(command->m_type == CMD_LOAD_SOFT_BODY);
|
||||||
|
command->m_loadSoftBodyArguments.m_collisionHardness = collisionHardness;
|
||||||
|
command->m_updateFlags |= LOAD_SOFT_BODY_SET_COLLISION_HARDNESS;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
B3_SHARED_API int b3LoadSoftBodySetFrictionCoefficient(b3SharedMemoryCommandHandle commandHandle, double frictionCoefficient)
|
||||||
|
{
|
||||||
|
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
|
||||||
|
b3Assert(command->m_type == CMD_LOAD_SOFT_BODY);
|
||||||
|
command->m_loadSoftBodyArguments.m_frictionCoeff = frictionCoefficient;
|
||||||
|
command->m_updateFlags |= LOAD_SOFT_BODY_SET_FRICTION_COEFFICIENT;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
B3_SHARED_API int b3LoadSoftBodyUseBendingSprings(b3SharedMemoryCommandHandle commandHandle, int useBendingSprings)
|
||||||
|
{
|
||||||
|
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
|
||||||
|
b3Assert(command->m_type == CMD_LOAD_SOFT_BODY);
|
||||||
|
command->m_loadSoftBodyArguments.m_useBendingSprings = useBendingSprings;
|
||||||
|
command->m_updateFlags |= LOAD_SOFT_BODY_ADD_BENDING_SPRINGS;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
B3_SHARED_API b3SharedMemoryCommandHandle b3LoadUrdfCommandInit(b3PhysicsClientHandle physClient, const char* urdfFileName)
|
B3_SHARED_API b3SharedMemoryCommandHandle b3LoadUrdfCommandInit(b3PhysicsClientHandle physClient, const char* urdfFileName)
|
||||||
{
|
{
|
||||||
PhysicsClient* cl = (PhysicsClient*)physClient;
|
PhysicsClient* cl = (PhysicsClient*)physClient;
|
||||||
@@ -1373,7 +1441,6 @@ B3_SHARED_API int b3CreateCollisionShapeAddHeightfield2(b3PhysicsClientHandle ph
|
|||||||
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_numHeightfieldRows = numHeightfieldRows;
|
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_numHeightfieldRows = numHeightfieldRows;
|
||||||
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_numHeightfieldColumns = numHeightfieldColumns;
|
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_numHeightfieldColumns = numHeightfieldColumns;
|
||||||
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_replaceHeightfieldIndex = replaceHeightfieldIndex;
|
command->m_createUserShapeArgs.m_shapes[shapeIndex].m_replaceHeightfieldIndex = replaceHeightfieldIndex;
|
||||||
|
|
||||||
cl->uploadBulletFileToSharedMemory((const char*)heightfieldData, numHeightfieldRows*numHeightfieldColumns* sizeof(float));
|
cl->uploadBulletFileToSharedMemory((const char*)heightfieldData, numHeightfieldRows*numHeightfieldColumns* sizeof(float));
|
||||||
command->m_createUserShapeArgs.m_numUserShapes++;
|
command->m_createUserShapeArgs.m_numUserShapes++;
|
||||||
return shapeIndex;
|
return shapeIndex;
|
||||||
|
|||||||
@@ -631,6 +631,13 @@ extern "C"
|
|||||||
B3_SHARED_API int b3LoadSoftBodySetCollisionMargin(b3SharedMemoryCommandHandle commandHandle, double collisionMargin);
|
B3_SHARED_API int b3LoadSoftBodySetCollisionMargin(b3SharedMemoryCommandHandle commandHandle, double collisionMargin);
|
||||||
B3_SHARED_API int b3LoadSoftBodySetStartPosition(b3SharedMemoryCommandHandle commandHandle, double startPosX, double startPosY, double startPosZ);
|
B3_SHARED_API int b3LoadSoftBodySetStartPosition(b3SharedMemoryCommandHandle commandHandle, double startPosX, double startPosY, double startPosZ);
|
||||||
B3_SHARED_API int b3LoadSoftBodySetStartOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX, double startOrnY, double startOrnZ, double startOrnW);
|
B3_SHARED_API int b3LoadSoftBodySetStartOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX, double startOrnY, double startOrnZ, double startOrnW);
|
||||||
|
B3_SHARED_API int b3LoadSoftBodyAddCorotatedForce(b3SharedMemoryCommandHandle commandHandle, double corotatedMu, double corotatedLambda);
|
||||||
|
B3_SHARED_API int b3LoadSoftBodyAddNeoHookeanForce(b3SharedMemoryCommandHandle commandHandle, double NeoHookeanMu, double NeoHookeanLambda);
|
||||||
|
B3_SHARED_API int b3LoadSoftBodyAddMassSpringForce(b3SharedMemoryCommandHandle commandHandle, double springElasticStiffness , double springDampingStiffness);
|
||||||
|
B3_SHARED_API int b3LoadSoftBodyAddGravityForce(b3SharedMemoryCommandHandle commandHandle, double gravityX, double gravityY, double gravityZ);
|
||||||
|
B3_SHARED_API int b3LoadSoftBodySetCollsionHardness(b3SharedMemoryCommandHandle commandHandle, double collisionHardness);
|
||||||
|
B3_SHARED_API int b3LoadSoftBodySetFrictionCoefficient(b3SharedMemoryCommandHandle commandHandle, double frictionCoefficient);
|
||||||
|
B3_SHARED_API int b3LoadSoftBodyUseBendingSprings(b3SharedMemoryCommandHandle commandHandle, int useBendingSprings);
|
||||||
|
|
||||||
B3_SHARED_API b3SharedMemoryCommandHandle b3RequestVREventsCommandInit(b3PhysicsClientHandle physClient);
|
B3_SHARED_API b3SharedMemoryCommandHandle b3RequestVREventsCommandInit(b3PhysicsClientHandle physClient);
|
||||||
B3_SHARED_API void b3VREventsSetDeviceTypeFilter(b3SharedMemoryCommandHandle commandHandle, int deviceTypeFilter);
|
B3_SHARED_API void b3VREventsSetDeviceTypeFilter(b3SharedMemoryCommandHandle commandHandle, int deviceTypeFilter);
|
||||||
|
|||||||
@@ -101,7 +101,11 @@
|
|||||||
#include "BulletSoftBody/btSoftBodySolvers.h"
|
#include "BulletSoftBody/btSoftBodySolvers.h"
|
||||||
#include "BulletSoftBody/btSoftBodyHelpers.h"
|
#include "BulletSoftBody/btSoftBodyHelpers.h"
|
||||||
#include "BulletSoftBody/btSoftMultiBodyDynamicsWorld.h"
|
#include "BulletSoftBody/btSoftMultiBodyDynamicsWorld.h"
|
||||||
|
#include "BulletSoftBody/btDeformableMultiBodyDynamicsWorld.h"
|
||||||
|
#include "BulletSoftBody/btDeformableBodySolver.h"
|
||||||
|
#include "BulletSoftBody/btDeformableMultiBodyConstraintSolver.h"
|
||||||
#include "../SoftDemo/BunnyMesh.h"
|
#include "../SoftDemo/BunnyMesh.h"
|
||||||
|
#define SKIP_DEFORMABLE_BODY
|
||||||
#else
|
#else
|
||||||
#include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h"
|
#include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h"
|
||||||
#endif
|
#endif
|
||||||
@@ -1619,12 +1623,22 @@ struct PhysicsServerCommandProcessorInternalData
|
|||||||
btHashedOverlappingPairCache* m_pairCache;
|
btHashedOverlappingPairCache* m_pairCache;
|
||||||
btBroadphaseInterface* m_broadphase;
|
btBroadphaseInterface* m_broadphase;
|
||||||
btCollisionDispatcher* m_dispatcher;
|
btCollisionDispatcher* m_dispatcher;
|
||||||
|
#ifdef SKIP_DEFORMABLE_BODY
|
||||||
btMultiBodyConstraintSolver* m_solver;
|
btMultiBodyConstraintSolver* m_solver;
|
||||||
|
#else
|
||||||
|
btDeformableMultiBodyConstraintSolver* m_solver;
|
||||||
|
#endif
|
||||||
|
|
||||||
btDefaultCollisionConfiguration* m_collisionConfiguration;
|
btDefaultCollisionConfiguration* m_collisionConfiguration;
|
||||||
|
|
||||||
#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
|
#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
|
||||||
|
#ifndef SKIP_DEFORMABLE_BODY
|
||||||
|
btDeformableMultiBodyDynamicsWorld* m_dynamicsWorld;
|
||||||
|
btDeformableBodySolver* m_deformablebodySolver;
|
||||||
|
#else
|
||||||
btSoftMultiBodyDynamicsWorld* m_dynamicsWorld;
|
btSoftMultiBodyDynamicsWorld* m_dynamicsWorld;
|
||||||
btSoftBodySolver* m_softbodySolver;
|
btSoftBodySolver* m_softbodySolver;
|
||||||
|
#endif
|
||||||
#else
|
#else
|
||||||
btMultiBodyDynamicsWorld* m_dynamicsWorld;
|
btMultiBodyDynamicsWorld* m_dynamicsWorld;
|
||||||
#endif
|
#endif
|
||||||
@@ -2607,10 +2621,19 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld()
|
|||||||
bv->setVelocityPrediction(0);
|
bv->setVelocityPrediction(0);
|
||||||
m_data->m_broadphase = bv;
|
m_data->m_broadphase = bv;
|
||||||
|
|
||||||
|
#ifdef SKIP_DEFORMABLE_BODY
|
||||||
m_data->m_solver = new btMultiBodyConstraintSolver;
|
m_data->m_solver = new btMultiBodyConstraintSolver;
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
|
#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
|
||||||
|
#ifndef SKIP_DEFORMABLE_BODY
|
||||||
|
m_data->m_deformablebodySolver = new btDeformableBodySolver();
|
||||||
|
m_data->m_solver = new btDeformableMultiBodyConstraintSolver;
|
||||||
|
m_data->m_solver->setDeformableSolver(m_data->m_deformablebodySolver);
|
||||||
|
m_data->m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration, m_data->m_deformablebodySolver);
|
||||||
|
#else
|
||||||
m_data->m_dynamicsWorld = new btSoftMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration);
|
m_data->m_dynamicsWorld = new btSoftMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration);
|
||||||
|
#endif
|
||||||
#else
|
#else
|
||||||
m_data->m_dynamicsWorld = new btMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration);
|
m_data->m_dynamicsWorld = new btMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration);
|
||||||
#endif
|
#endif
|
||||||
@@ -2775,7 +2798,9 @@ void PhysicsServerCommandProcessor::deleteDynamicsWorld()
|
|||||||
for (i = m_data->m_dynamicsWorld->getSoftBodyArray().size() - 1; i >= 0; i--)
|
for (i = m_data->m_dynamicsWorld->getSoftBodyArray().size() - 1; i >= 0; i--)
|
||||||
{
|
{
|
||||||
btSoftBody* sb = m_data->m_dynamicsWorld->getSoftBodyArray()[i];
|
btSoftBody* sb = m_data->m_dynamicsWorld->getSoftBodyArray()[i];
|
||||||
|
#ifdef SKIP_DEFORMABLE_BODY
|
||||||
m_data->m_dynamicsWorld->removeSoftBody(sb);
|
m_data->m_dynamicsWorld->removeSoftBody(sb);
|
||||||
|
#endif
|
||||||
delete sb;
|
delete sb;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
@@ -4728,7 +4753,6 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str
|
|||||||
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
case GEOM_MESH:
|
case GEOM_MESH:
|
||||||
{
|
{
|
||||||
btVector3 meshScale(clientCmd.m_createUserShapeArgs.m_shapes[i].m_meshScale[0],
|
btVector3 meshScale(clientCmd.m_createUserShapeArgs.m_shapes[i].m_meshScale[0],
|
||||||
@@ -4909,6 +4933,7 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str
|
|||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
default:
|
default:
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
@@ -8014,6 +8039,9 @@ bool PhysicsServerCommandProcessor::processLoadSoftBodyCommand(const struct Shar
|
|||||||
int out_type;
|
int out_type;
|
||||||
|
|
||||||
bool foundFile = UrdfFindMeshFile(fileIO, pathPrefix, relativeFileName, error_message_prefix, &out_found_filename, &out_type);
|
bool foundFile = UrdfFindMeshFile(fileIO, pathPrefix, relativeFileName, error_message_prefix, &out_found_filename, &out_type);
|
||||||
|
btSoftBody* psb = NULL;
|
||||||
|
if (out_type == UrdfGeometry::FILE_OBJ)
|
||||||
|
{
|
||||||
std::vector<tinyobj::shape_t> shapes;
|
std::vector<tinyobj::shape_t> shapes;
|
||||||
tinyobj::attrib_t attribute;
|
tinyobj::attrib_t attribute;
|
||||||
std::string err = tinyobj::LoadObj(attribute, shapes, out_found_filename.c_str(), "", fileIO);
|
std::string err = tinyobj::LoadObj(attribute, shapes, out_found_filename.c_str(), "", fileIO);
|
||||||
@@ -8033,7 +8061,91 @@ bool PhysicsServerCommandProcessor::processLoadSoftBodyCommand(const struct Shar
|
|||||||
int numTris = shape.mesh.indices.size() / 3;
|
int numTris = shape.mesh.indices.size() / 3;
|
||||||
if (numTris > 0)
|
if (numTris > 0)
|
||||||
{
|
{
|
||||||
btSoftBody* psb = btSoftBodyHelpers::CreateFromTriMesh(m_data->m_dynamicsWorld->getWorldInfo(), &vertices[0], &indices[0], numTris);
|
psb = btSoftBodyHelpers::CreateFromTriMesh(m_data->m_dynamicsWorld->getWorldInfo(), &vertices[0], &indices[0], numTris);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if (out_type = UrdfGeometry::FILE_VTK)
|
||||||
|
{
|
||||||
|
#ifndef SKIP_DEFORMABLE_BODY
|
||||||
|
psb = btSoftBodyHelpers::CreateFromVtkFile(m_data->m_dynamicsWorld->getWorldInfo(), out_found_filename.c_str());
|
||||||
|
btScalar corotated_mu, corotated_lambda;
|
||||||
|
btScalar spring_elastic_stiffness, spring_damping_stiffness;
|
||||||
|
btScalar gravity_constant;
|
||||||
|
if (clientCmd.m_updateFlags & LOAD_SOFT_BODY_ADD_COROTATED_FORCE)
|
||||||
|
{
|
||||||
|
corotated_mu = clientCmd.m_loadSoftBodyArguments.m_corotatedMu;
|
||||||
|
corotated_lambda = clientCmd.m_loadSoftBodyArguments.m_corotatedLambda;
|
||||||
|
m_data->m_dynamicsWorld->addForce(psb, new btDeformableCorotatedForce(corotated_mu, corotated_lambda));
|
||||||
|
}
|
||||||
|
btScalar neohookean_mu, neohookean_lambda;
|
||||||
|
if (clientCmd.m_updateFlags & LOAD_SOFT_BODY_ADD_NEOHOOKEAN_FORCE)
|
||||||
|
{
|
||||||
|
neohookean_mu = clientCmd.m_loadSoftBodyArguments.m_NeoHookeanMu;
|
||||||
|
neohookean_lambda = clientCmd.m_loadSoftBodyArguments.m_NeoHookeanLambda;
|
||||||
|
m_data->m_dynamicsWorld->addForce(psb, new btDeformableNeoHookeanForce(neohookean_mu, neohookean_lambda));
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
if (psb != NULL)
|
||||||
|
{
|
||||||
|
#ifndef SKIP_DEFORMABLE_BODY
|
||||||
|
btScalar corotated_mu, corotated_lambda;
|
||||||
|
btScalar spring_elastic_stiffness, spring_damping_stiffness;
|
||||||
|
btScalar gravity_constant;
|
||||||
|
if (clientCmd.m_updateFlags & LOAD_SOFT_BODY_ADD_COROTATED_FORCE)
|
||||||
|
{
|
||||||
|
corotated_mu = clientCmd.m_loadSoftBodyArguments.m_corotatedMu;
|
||||||
|
corotated_lambda = clientCmd.m_loadSoftBodyArguments.m_corotatedLambda;
|
||||||
|
m_data->m_dynamicsWorld->addForce(psb, new btDeformableCorotatedForce(corotated_mu, corotated_lambda));
|
||||||
|
}
|
||||||
|
if (clientCmd.m_updateFlags & LOAD_SOFT_BODY_ADD_MASS_SPRING_FORCE)
|
||||||
|
{
|
||||||
|
spring_elastic_stiffness = clientCmd.m_loadSoftBodyArguments.m_springElasticStiffness;
|
||||||
|
spring_damping_stiffness = clientCmd.m_loadSoftBodyArguments.m_springDampingStiffness;
|
||||||
|
m_data->m_dynamicsWorld->addForce(psb, new btDeformableMassSpringForce(spring_elastic_stiffness, spring_damping_stiffness, false));
|
||||||
|
}
|
||||||
|
btVector3 gravity(0,0,0);
|
||||||
|
if (clientCmd.m_updateFlags & LOAD_SOFT_BODY_ADD_GRAVITY_FORCE)
|
||||||
|
{
|
||||||
|
gravity[0] = loadSoftBodyArgs.m_gravity[0];
|
||||||
|
gravity[1] = loadSoftBodyArgs.m_gravity[1];
|
||||||
|
gravity[2] = loadSoftBodyArgs.m_gravity[2];
|
||||||
|
m_data->m_dynamicsWorld->addForce(psb, new btDeformableGravityForce(gravity));
|
||||||
|
}
|
||||||
|
btScalar collision_hardness = 1;
|
||||||
|
if (clientCmd.m_updateFlags & LOAD_SOFT_BODY_SET_COLLISION_HARDNESS)
|
||||||
|
{
|
||||||
|
collision_hardness = loadSoftBodyArgs.m_collisionHardness;
|
||||||
|
}
|
||||||
|
psb->m_cfg.kKHR = collision_hardness;
|
||||||
|
psb->m_cfg.kCHR = collision_hardness;
|
||||||
|
|
||||||
|
btScalar friction_coeff = 0;
|
||||||
|
if (clientCmd.m_updateFlags & LOAD_SOFT_BODY_SET_FRICTION_COEFFICIENT)
|
||||||
|
{
|
||||||
|
friction_coeff = loadSoftBodyArgs.m_frictionCoeff;
|
||||||
|
}
|
||||||
|
psb->m_cfg.kDF = friction_coeff;
|
||||||
|
|
||||||
|
bool use_bending_spring = true;
|
||||||
|
if (clientCmd.m_updateFlags & LOAD_SOFT_BODY_ADD_BENDING_SPRINGS)
|
||||||
|
{
|
||||||
|
use_bending_spring = loadSoftBodyArgs.m_useBendingSprings;
|
||||||
|
}
|
||||||
|
btSoftBody::Material* pm = psb->appendMaterial();
|
||||||
|
pm->m_flags -= btSoftBody::fMaterial::DebugDraw;
|
||||||
|
if (use_bending_spring)
|
||||||
|
{
|
||||||
|
psb->generateBendingConstraints(2,pm);
|
||||||
|
}
|
||||||
|
|
||||||
|
// turn on the collision flag for deformable
|
||||||
|
// collision
|
||||||
|
psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD;
|
||||||
|
psb->setCollisionFlags(0);
|
||||||
|
psb->setTotalMass(mass);
|
||||||
|
#else
|
||||||
btSoftBody::Material* pm = psb->appendMaterial();
|
btSoftBody::Material* pm = psb->appendMaterial();
|
||||||
pm->m_kLST = 0.5;
|
pm->m_kLST = 0.5;
|
||||||
pm->m_flags -= btSoftBody::fMaterial::DebugDraw;
|
pm->m_flags -= btSoftBody::fMaterial::DebugDraw;
|
||||||
@@ -8043,11 +8155,12 @@ bool PhysicsServerCommandProcessor::processLoadSoftBodyCommand(const struct Shar
|
|||||||
//turn on softbody vs softbody collision
|
//turn on softbody vs softbody collision
|
||||||
psb->m_cfg.collisions |= btSoftBody::fCollision::VF_SS;
|
psb->m_cfg.collisions |= btSoftBody::fCollision::VF_SS;
|
||||||
psb->randomizeConstraints();
|
psb->randomizeConstraints();
|
||||||
|
psb->setTotalMass(mass, true);
|
||||||
|
#endif
|
||||||
psb->scale(btVector3(scale, scale, scale));
|
psb->scale(btVector3(scale, scale, scale));
|
||||||
psb->rotate(initialOrn);
|
psb->rotate(initialOrn);
|
||||||
psb->translate(initialPos);
|
psb->translate(initialPos);
|
||||||
|
|
||||||
psb->setTotalMass(mass, true);
|
|
||||||
psb->getCollisionShape()->setMargin(collisionMargin);
|
psb->getCollisionShape()->setMargin(collisionMargin);
|
||||||
psb->getCollisionShape()->setUserPointer(psb);
|
psb->getCollisionShape()->setUserPointer(psb);
|
||||||
m_data->m_dynamicsWorld->addSoftBody(psb);
|
m_data->m_dynamicsWorld->addSoftBody(psb);
|
||||||
@@ -8110,8 +8223,6 @@ bool PhysicsServerCommandProcessor::processLoadSoftBodyCommand(const struct Shar
|
|||||||
m_data->m_pluginManager.addNotification(notification);
|
m_data->m_pluginManager.addNotification(notification);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
return hasStatus;
|
return hasStatus;
|
||||||
}
|
}
|
||||||
@@ -9134,6 +9245,7 @@ bool PhysicsServerCommandProcessor::processSendPhysicsParametersCommand(const st
|
|||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#ifdef SKIP_DEFORMABLE_BODY
|
||||||
if (newSolver)
|
if (newSolver)
|
||||||
{
|
{
|
||||||
delete oldSolver;
|
delete oldSolver;
|
||||||
@@ -9142,6 +9254,7 @@ bool PhysicsServerCommandProcessor::processSendPhysicsParametersCommand(const st
|
|||||||
m_data->m_solver = newSolver;
|
m_data->m_solver = newSolver;
|
||||||
printf("switched solver\n");
|
printf("switched solver\n");
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -10281,10 +10394,14 @@ bool PhysicsServerCommandProcessor::processRemoveBodyCommand(const struct Shared
|
|||||||
btSoftBody* psb = bodyHandle->m_softBody;
|
btSoftBody* psb = bodyHandle->m_softBody;
|
||||||
if (m_data->m_pluginManager.getRenderInterface())
|
if (m_data->m_pluginManager.getRenderInterface())
|
||||||
{
|
{
|
||||||
|
#ifdef SKIP_DEFORMABLE_BODY
|
||||||
m_data->m_pluginManager.getRenderInterface()->removeVisualShape(psb->getBroadphaseHandle()->getUid());
|
m_data->m_pluginManager.getRenderInterface()->removeVisualShape(psb->getBroadphaseHandle()->getUid());
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
serverCmd.m_removeObjectArgs.m_bodyUniqueIds[serverCmd.m_removeObjectArgs.m_numBodies++] = bodyUniqueId;
|
serverCmd.m_removeObjectArgs.m_bodyUniqueIds[serverCmd.m_removeObjectArgs.m_numBodies++] = bodyUniqueId;
|
||||||
|
#ifdef SKIP_DEFORMABLE_BODY
|
||||||
m_data->m_dynamicsWorld->removeSoftBody(psb);
|
m_data->m_dynamicsWorld->removeSoftBody(psb);
|
||||||
|
#endif
|
||||||
int graphicsInstance = psb->getUserIndex2();
|
int graphicsInstance = psb->getUserIndex2();
|
||||||
m_data->m_guiHelper->removeGraphicsInstance(graphicsInstance);
|
m_data->m_guiHelper->removeGraphicsInstance(graphicsInstance);
|
||||||
delete psb;
|
delete psb;
|
||||||
@@ -12716,6 +12833,20 @@ void PhysicsServerCommandProcessor::renderScene(int renderFlags)
|
|||||||
}
|
}
|
||||||
|
|
||||||
m_data->m_guiHelper->render(m_data->m_dynamicsWorld);
|
m_data->m_guiHelper->render(m_data->m_dynamicsWorld);
|
||||||
|
#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
|
||||||
|
#ifndef SKIP_DEFORMABLE_BODY
|
||||||
|
for (int i = 0; i < m_data->m_dynamicsWorld->getSoftBodyArray().size(); i++)
|
||||||
|
{
|
||||||
|
btSoftBody* psb = (btSoftBody*)m_data->m_dynamicsWorld->getSoftBodyArray()[i];
|
||||||
|
{
|
||||||
|
btSoftBodyHelpers::DrawFrame(psb, m_data->m_dynamicsWorld->getDebugDrawer());
|
||||||
|
btSoftBodyHelpers::Draw(psb, m_data->m_dynamicsWorld->getDebugDrawer(), m_data->m_dynamicsWorld->getDrawFlags());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
m_data->m_guiHelper->drawDebugDrawerLines();
|
||||||
|
m_data->m_guiHelper->clearLines();
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -546,7 +546,7 @@ MultithreadedDebugDrawer : public btIDebugDraw
|
|||||||
btHashMap<ColorWidth, int> m_hashedLines;
|
btHashMap<ColorWidth, int> m_hashedLines;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
void drawDebugDrawerLines()
|
virtual void drawDebugDrawerLines()
|
||||||
{
|
{
|
||||||
if (m_hashedLines.size())
|
if (m_hashedLines.size())
|
||||||
{
|
{
|
||||||
@@ -628,7 +628,7 @@ public:
|
|||||||
return m_debugMode;
|
return m_debugMode;
|
||||||
}
|
}
|
||||||
|
|
||||||
virtual void clearLines()
|
virtual void clearLines() override
|
||||||
{
|
{
|
||||||
m_hashedLines.clear();
|
m_hashedLines.clear();
|
||||||
m_sortedIndices.clear();
|
m_sortedIndices.clear();
|
||||||
@@ -650,13 +650,21 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface
|
|||||||
|
|
||||||
public:
|
public:
|
||||||
MultithreadedDebugDrawer* m_debugDraw;
|
MultithreadedDebugDrawer* m_debugDraw;
|
||||||
void drawDebugDrawerLines()
|
virtual void drawDebugDrawerLines()
|
||||||
{
|
{
|
||||||
if (m_debugDraw)
|
if (m_debugDraw)
|
||||||
{
|
{
|
||||||
m_debugDraw->drawDebugDrawerLines();
|
m_debugDraw->drawDebugDrawerLines();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
virtual void clearLines()
|
||||||
|
{
|
||||||
|
if (m_debugDraw)
|
||||||
|
{
|
||||||
|
m_debugDraw->clearLines();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
GUIHelperInterface* m_childGuiHelper;
|
GUIHelperInterface* m_childGuiHelper;
|
||||||
|
|
||||||
btHashMap<btHashPtr, int> m_cachedTextureIds;
|
btHashMap<btHashPtr, int> m_cachedTextureIds;
|
||||||
@@ -847,9 +855,7 @@ public:
|
|||||||
delete m_debugDraw;
|
delete m_debugDraw;
|
||||||
m_debugDraw = 0;
|
m_debugDraw = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
m_debugDraw = new MultithreadedDebugDrawer(this);
|
m_debugDraw = new MultithreadedDebugDrawer(this);
|
||||||
|
|
||||||
rbWorld->setDebugDrawer(m_debugDraw);
|
rbWorld->setDebugDrawer(m_debugDraw);
|
||||||
|
|
||||||
//m_childGuiHelper->createPhysicsDebugDrawer(rbWorld);
|
//m_childGuiHelper->createPhysicsDebugDrawer(rbWorld);
|
||||||
|
|||||||
@@ -489,11 +489,18 @@ enum EnumSimParamUpdateFlags
|
|||||||
enum EnumLoadSoftBodyUpdateFlags
|
enum EnumLoadSoftBodyUpdateFlags
|
||||||
{
|
{
|
||||||
LOAD_SOFT_BODY_FILE_NAME = 1,
|
LOAD_SOFT_BODY_FILE_NAME = 1,
|
||||||
LOAD_SOFT_BODY_UPDATE_SCALE = 2,
|
LOAD_SOFT_BODY_UPDATE_SCALE = 1<<1,
|
||||||
LOAD_SOFT_BODY_UPDATE_MASS = 4,
|
LOAD_SOFT_BODY_UPDATE_MASS = 1<<2,
|
||||||
LOAD_SOFT_BODY_UPDATE_COLLISION_MARGIN = 8,
|
LOAD_SOFT_BODY_UPDATE_COLLISION_MARGIN = 1<<3,
|
||||||
LOAD_SOFT_BODY_INITIAL_POSITION = 16,
|
LOAD_SOFT_BODY_INITIAL_POSITION = 1<<4,
|
||||||
LOAD_SOFT_BODY_INITIAL_ORIENTATION = 32
|
LOAD_SOFT_BODY_INITIAL_ORIENTATION = 1<<5,
|
||||||
|
LOAD_SOFT_BODY_ADD_COROTATED_FORCE = 1<<6,
|
||||||
|
LOAD_SOFT_BODY_ADD_MASS_SPRING_FORCE = 1<<7,
|
||||||
|
LOAD_SOFT_BODY_ADD_GRAVITY_FORCE = 1<<8,
|
||||||
|
LOAD_SOFT_BODY_SET_COLLISION_HARDNESS = 1<<9,
|
||||||
|
LOAD_SOFT_BODY_SET_FRICTION_COEFFICIENT = 1<<10,
|
||||||
|
LOAD_SOFT_BODY_ADD_BENDING_SPRINGS = 1<<11,
|
||||||
|
LOAD_SOFT_BODY_ADD_NEOHOOKEAN_FORCE = 1<<12,
|
||||||
};
|
};
|
||||||
|
|
||||||
enum EnumSimParamInternalSimFlags
|
enum EnumSimParamInternalSimFlags
|
||||||
@@ -512,6 +519,16 @@ struct LoadSoftBodyArgs
|
|||||||
double m_collisionMargin;
|
double m_collisionMargin;
|
||||||
double m_initialPosition[3];
|
double m_initialPosition[3];
|
||||||
double m_initialOrientation[4];
|
double m_initialOrientation[4];
|
||||||
|
double m_springElasticStiffness;
|
||||||
|
double m_springDampingStiffness;
|
||||||
|
double m_corotatedMu;
|
||||||
|
double m_corotatedLambda;
|
||||||
|
double m_gravity[3];
|
||||||
|
bool m_useBendingSprings;
|
||||||
|
double m_collisionHardness;
|
||||||
|
double m_frictionCoeff;
|
||||||
|
double m_NeoHookeanMu;
|
||||||
|
double m_NeoHookeanLambda;
|
||||||
};
|
};
|
||||||
|
|
||||||
struct b3LoadSoftBodyResultArgs
|
struct b3LoadSoftBodyResultArgs
|
||||||
|
|||||||
Reference in New Issue
Block a user