Merge pull request #2509 from xhan0619/separate-bending-stiffness
Separate in-plane and bending stiffness for mass spring model
This commit is contained in:
@@ -422,11 +422,12 @@ B3_SHARED_API int b3LoadSoftBodySetFrictionCoefficient(b3SharedMemoryCommandHand
|
||||
return 0;
|
||||
}
|
||||
|
||||
B3_SHARED_API int b3LoadSoftBodyUseBendingSprings(b3SharedMemoryCommandHandle commandHandle, int useBendingSprings)
|
||||
B3_SHARED_API int b3LoadSoftBodyUseBendingSprings(b3SharedMemoryCommandHandle commandHandle, int useBendingSprings, double bendingStiffness)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
|
||||
b3Assert(command->m_type == CMD_LOAD_SOFT_BODY);
|
||||
command->m_loadSoftBodyArguments.m_useBendingSprings = useBendingSprings;
|
||||
command->m_loadSoftBodyArguments.m_useBendingSprings = useBendingSprings;
|
||||
command->m_loadSoftBodyArguments.m_springBendingStiffness = bendingStiffness;
|
||||
command->m_updateFlags |= LOAD_SOFT_BODY_ADD_BENDING_SPRINGS;
|
||||
return 0;
|
||||
}
|
||||
|
||||
@@ -643,7 +643,7 @@ extern "C"
|
||||
B3_SHARED_API int b3LoadSoftBodySetSelfCollision(b3SharedMemoryCommandHandle commandHandle, int useSelfCollision);
|
||||
B3_SHARED_API int b3LoadSoftBodyUseFaceContact(b3SharedMemoryCommandHandle commandHandle, int useFaceContact);
|
||||
B3_SHARED_API int b3LoadSoftBodySetFrictionCoefficient(b3SharedMemoryCommandHandle commandHandle, double frictionCoefficient);
|
||||
B3_SHARED_API int b3LoadSoftBodyUseBendingSprings(b3SharedMemoryCommandHandle commandHandle, int useBendingSprings);
|
||||
B3_SHARED_API int b3LoadSoftBodyUseBendingSprings(b3SharedMemoryCommandHandle commandHandle, int useBendingSprings, double bendingStiffness);
|
||||
|
||||
B3_SHARED_API b3SharedMemoryCommandHandle b3InitCreateSoftBodyAnchorConstraintCommand(b3PhysicsClientHandle physClient, int softBodyUniqueId, int nodeIndex, int bodyUniqueId, int linkIndex, const double bodyFramePosition[3]);
|
||||
|
||||
|
||||
@@ -8069,7 +8069,7 @@ bool PhysicsServerCommandProcessor::processLoadSoftBodyCommand(const struct Shar
|
||||
{
|
||||
collisionMargin = clientCmd.m_loadSoftBodyArguments.m_collisionMargin;
|
||||
}
|
||||
|
||||
btScalar spring_bending_stiffness = 0;
|
||||
{
|
||||
btSoftBody* psb = NULL;
|
||||
|
||||
@@ -8136,7 +8136,7 @@ bool PhysicsServerCommandProcessor::processLoadSoftBodyCommand(const struct Shar
|
||||
}
|
||||
}
|
||||
#ifndef SKIP_DEFORMABLE_BODY
|
||||
btScalar spring_elastic_stiffness, spring_damping_stiffness;
|
||||
btScalar spring_elastic_stiffness, spring_damping_stiffness;
|
||||
if (clientCmd.m_updateFlags & LOAD_SOFT_BODY_ADD_MASS_SPRING_FORCE)
|
||||
{
|
||||
btDeformableMultiBodyDynamicsWorld* deformWorld = getDeformableWorld();
|
||||
@@ -8144,7 +8144,11 @@ bool PhysicsServerCommandProcessor::processLoadSoftBodyCommand(const struct Shar
|
||||
{
|
||||
spring_elastic_stiffness = clientCmd.m_loadSoftBodyArguments.m_springElasticStiffness;
|
||||
spring_damping_stiffness = clientCmd.m_loadSoftBodyArguments.m_springDampingStiffness;
|
||||
btDeformableLagrangianForce* springForce = new btDeformableMassSpringForce(spring_elastic_stiffness, spring_damping_stiffness, false);
|
||||
if (clientCmd.m_updateFlags & LOAD_SOFT_BODY_ADD_BENDING_SPRINGS)
|
||||
{
|
||||
spring_bending_stiffness = clientCmd.m_loadSoftBodyArguments.m_springBendingStiffness;
|
||||
}
|
||||
btDeformableLagrangianForce* springForce = new btDeformableMassSpringForce(spring_elastic_stiffness, spring_damping_stiffness, false, spring_bending_stiffness);
|
||||
deformWorld->addForce(psb, springForce);
|
||||
m_data->m_lf.push_back(springForce);
|
||||
}
|
||||
@@ -8177,12 +8181,16 @@ bool PhysicsServerCommandProcessor::processLoadSoftBodyCommand(const struct Shar
|
||||
deformWorld->addForce(psb, neohookeanForce);
|
||||
m_data->m_lf.push_back(neohookeanForce);
|
||||
}
|
||||
btScalar spring_elastic_stiffness, spring_damping_stiffness;
|
||||
btScalar spring_elastic_stiffness, spring_damping_stiffness;
|
||||
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;
|
||||
btDeformableLagrangianForce* springForce = new btDeformableMassSpringForce(spring_elastic_stiffness, spring_damping_stiffness, true);
|
||||
if (clientCmd.m_updateFlags & LOAD_SOFT_BODY_ADD_BENDING_SPRINGS)
|
||||
{
|
||||
spring_bending_stiffness = clientCmd.m_loadSoftBodyArguments.m_springBendingStiffness;
|
||||
}
|
||||
btDeformableLagrangianForce* springForce = new btDeformableMassSpringForce(spring_elastic_stiffness, spring_damping_stiffness, true, spring_bending_stiffness);
|
||||
deformWorld->addForce(psb, springForce);
|
||||
m_data->m_lf.push_back(springForce);
|
||||
}
|
||||
@@ -8257,19 +8265,18 @@ bool PhysicsServerCommandProcessor::processLoadSoftBodyCommand(const struct Shar
|
||||
friction_coeff = loadSoftBodyArgs.m_frictionCoeff;
|
||||
}
|
||||
psb->m_cfg.kDF = friction_coeff;
|
||||
|
||||
bool use_bending_spring = true;
|
||||
bool use_bending_spring = false;
|
||||
if (clientCmd.m_updateFlags & LOAD_SOFT_BODY_ADD_BENDING_SPRINGS)
|
||||
{
|
||||
use_bending_spring = loadSoftBodyArgs.m_useBendingSprings;
|
||||
use_bending_spring = loadSoftBodyArgs.m_useBendingSprings;
|
||||
if (use_bending_spring)
|
||||
{
|
||||
psb->generateBendingConstraints(2);
|
||||
}
|
||||
}
|
||||
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 between deformable and rigid
|
||||
psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD;
|
||||
|
||||
@@ -523,18 +523,19 @@ struct LoadSoftBodyArgs
|
||||
double m_mass;
|
||||
double m_collisionMargin;
|
||||
double m_initialPosition[3];
|
||||
double m_initialOrientation[4];
|
||||
double m_springElasticStiffness;
|
||||
double m_springDampingStiffness;
|
||||
double m_corotatedMu;
|
||||
double m_corotatedLambda;
|
||||
int m_useBendingSprings;
|
||||
double m_collisionHardness;
|
||||
double m_useSelfCollision;
|
||||
double m_frictionCoeff;
|
||||
double m_NeoHookeanMu;
|
||||
double m_NeoHookeanLambda;
|
||||
double m_NeoHookeanDamping;
|
||||
double m_initialOrientation[4];
|
||||
double m_springElasticStiffness;
|
||||
double m_springDampingStiffness;
|
||||
double m_springBendingStiffness;
|
||||
double m_corotatedMu;
|
||||
double m_corotatedLambda;
|
||||
int m_useBendingSprings;
|
||||
double m_collisionHardness;
|
||||
double m_useSelfCollision;
|
||||
double m_frictionCoeff;
|
||||
double m_NeoHookeanMu;
|
||||
double m_NeoHookeanLambda;
|
||||
double m_NeoHookeanDamping;
|
||||
int m_useFaceContact;
|
||||
char m_simFileName[MAX_FILENAME_LENGTH];
|
||||
};
|
||||
|
||||
@@ -7,8 +7,8 @@
|
||||
//Please don't replace an existing magic number:
|
||||
//instead, only ADD a new one at the top, comment-out previous one
|
||||
|
||||
|
||||
#define SHARED_MEMORY_MAGIC_NUMBER 201911180
|
||||
#define SHARED_MEMORY_MAGIC_NUMBER 201911280
|
||||
//#define SHARED_MEMORY_MAGIC_NUMBER 201911180
|
||||
//#define SHARED_MEMORY_MAGIC_NUMBER 201909030
|
||||
//#define SHARED_MEMORY_MAGIC_NUMBER 201908110
|
||||
//#define SHARED_MEMORY_MAGIC_NUMBER 201908050
|
||||
|
||||
@@ -1973,7 +1973,7 @@ static PyObject* pybullet_loadSoftBody(PyObject* self, PyObject* args, PyObject*
|
||||
int physicsClientId = 0;
|
||||
int flags = 0;
|
||||
|
||||
static char* kwlist[] = {"fileName", "basePosition", "baseOrientation", "scale", "mass", "collisionMargin", "physicsClientId", "useMassSpring", "useBendingSprings", "useNeoHookean", "springElasticStiffness", "springDampingStiffness", "NeoHookeanMu", "NeoHookeanLambda", "NeoHookeanDamping", "frictionCoeff", "useFaceContact", "useSelfCollision", NULL};
|
||||
static char* kwlist[] = {"fileName", "basePosition", "baseOrientation", "scale", "mass", "collisionMargin", "physicsClientId", "useMassSpring", "useBendingSprings", "useNeoHookean", "springElasticStiffness", "springDampingStiffness", "springBendingStiffness", "NeoHookeanMu", "NeoHookeanLambda", "NeoHookeanDamping", "frictionCoeff", "useFaceContact", "useSelfCollision", NULL};
|
||||
|
||||
int bodyUniqueId = -1;
|
||||
const char* fileName = "";
|
||||
@@ -1985,6 +1985,7 @@ static PyObject* pybullet_loadSoftBody(PyObject* self, PyObject* args, PyObject*
|
||||
int useNeoHookean = 0;
|
||||
double springElasticStiffness = 1;
|
||||
double springDampingStiffness = 0.1;
|
||||
double springBendingStiffness = 0.1;
|
||||
double NeoHookeanMu = 1;
|
||||
double NeoHookeanLambda = 1;
|
||||
double NeoHookeanDamping = 0.1;
|
||||
@@ -2002,7 +2003,7 @@ static PyObject* pybullet_loadSoftBody(PyObject* self, PyObject* args, PyObject*
|
||||
PyObject* basePosObj = 0;
|
||||
PyObject* baseOrnObj = 0;
|
||||
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|OOdddiiiiddddddii", kwlist, &fileName, &basePosObj, &baseOrnObj, &scale, &mass, &collisionMargin, &physicsClientId, &useMassSpring, &useBendingSprings, &useNeoHookean, &springElasticStiffness, &springDampingStiffness, &NeoHookeanMu, &NeoHookeanLambda, &NeoHookeanDamping, &frictionCoeff, &useFaceContact, &useSelfCollision))
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|OOdddiiiidddddddii", kwlist, &fileName, &basePosObj, &baseOrnObj, &scale, &mass, &collisionMargin, &physicsClientId, &useMassSpring, &useBendingSprings, &useNeoHookean, &springElasticStiffness, &springDampingStiffness, &springBendingStiffness, &NeoHookeanMu, &NeoHookeanLambda, &NeoHookeanDamping, &frictionCoeff, &useFaceContact, &useSelfCollision))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
@@ -2058,7 +2059,7 @@ static PyObject* pybullet_loadSoftBody(PyObject* self, PyObject* args, PyObject*
|
||||
if (useMassSpring)
|
||||
{
|
||||
b3LoadSoftBodyAddMassSpringForce(command, springElasticStiffness, springDampingStiffness);
|
||||
b3LoadSoftBodyUseBendingSprings(command, useBendingSprings);
|
||||
b3LoadSoftBodyUseBendingSprings(command, useBendingSprings, springBendingStiffness);
|
||||
}
|
||||
if (useNeoHookean)
|
||||
{
|
||||
|
||||
Reference in New Issue
Block a user