add API for two different damping modes for mass spring

This commit is contained in:
Xuchen Han 2020-05-11 16:42:17 -07:00
parent 15f3e144f6
commit 644fd5f311
6 changed files with 17 additions and 11 deletions

View File

@ -205,10 +205,12 @@ struct SpringCoeffcients{
double elastic_stiffness;
double damping_stiffness;
double bending_stiffness;
int damp_all_directions;
SpringCoeffcients():
elastic_stiffness(0.),
damping_stiffness(0.),
bending_stiffness(0.){}
elastic_stiffness(0.),
damping_stiffness(0.),
bending_stiffness(0.),
damp_all_directions(0){}
};
struct LameCoefficients

View File

@ -377,12 +377,13 @@ B3_SHARED_API int b3LoadSoftBodyAddNeoHookeanForce(b3SharedMemoryCommandHandle c
return 0;
}
B3_SHARED_API int b3LoadSoftBodyAddMassSpringForce(b3SharedMemoryCommandHandle commandHandle, double springElasticStiffness , double springDampingStiffness)
B3_SHARED_API int b3LoadSoftBodyAddMassSpringForce(b3SharedMemoryCommandHandle commandHandle, double springElasticStiffness , double springDampingStiffness, int dampAllDirections)
{
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_loadSoftBodyArguments.m_springElasticStiffness = springElasticStiffness;
command->m_loadSoftBodyArguments.m_springDampingStiffness = springDampingStiffness;
command->m_loadSoftBodyArguments.m_dampAllDirections = dampAllDirections;
command->m_updateFlags |= LOAD_SOFT_BODY_ADD_MASS_SPRING_FORCE;
return 0;
}

View File

@ -647,7 +647,7 @@ extern "C"
B3_SHARED_API int b3LoadSoftBodyAddCorotatedForce(b3SharedMemoryCommandHandle commandHandle, double corotatedMu, double corotatedLambda);
B3_SHARED_API int b3LoadSoftBodyAddCorotatedForce(b3SharedMemoryCommandHandle commandHandle, double corotatedMu, double corotatedLambda);
B3_SHARED_API int b3LoadSoftBodyAddNeoHookeanForce(b3SharedMemoryCommandHandle commandHandle, double NeoHookeanMu, double NeoHookeanLambda, double NeoHookeanDamping);
B3_SHARED_API int b3LoadSoftBodyAddMassSpringForce(b3SharedMemoryCommandHandle commandHandle, double springElasticStiffness , double springDampingStiffness);
B3_SHARED_API int b3LoadSoftBodyAddMassSpringForce(b3SharedMemoryCommandHandle commandHandle, double springElasticStiffness , double springDampingStiffness, int dampAllDirections = 0);
B3_SHARED_API int b3LoadSoftBodyAddGravityForce(b3SharedMemoryCommandHandle commandHandle, double gravityX, double gravityY, double gravityZ);
B3_SHARED_API int b3LoadSoftBodySetCollisionHardness(b3SharedMemoryCommandHandle commandHandle, double collisionHardness);
B3_SHARED_API int b3LoadSoftBodySetSelfCollision(b3SharedMemoryCommandHandle commandHandle, int useSelfCollision);

View File

@ -8362,6 +8362,7 @@ void constructUrdfDeformable(const struct SharedMemoryCommand& clientCmd, UrdfDe
#ifndef SKIP_DEFORMABLE_BODY
deformable.m_springCoefficients.elastic_stiffness = loadSoftBodyArgs.m_springElasticStiffness;
deformable.m_springCoefficients.damping_stiffness = loadSoftBodyArgs.m_springDampingStiffness;
deformable.m_springCoefficients.damp_all_directions = loadSoftBodyArgs.m_dampAllDirections;
if (clientCmd.m_updateFlags & LOAD_SOFT_BODY_ADD_BENDING_SPRINGS)
{
deformable.m_springCoefficients.bending_stiffness = loadSoftBodyArgs.m_springBendingStiffness;
@ -8472,7 +8473,7 @@ bool PhysicsServerCommandProcessor::processDeformable(const UrdfDeformable& defo
btDeformableLagrangianForce* springForce =
new btDeformableMassSpringForce(deformable.m_springCoefficients.elastic_stiffness,
deformable.m_springCoefficients.damping_stiffness,
true, deformable.m_springCoefficients.bending_stiffness);
deformable.m_springCoefficients.damp_all_directions, deformable.m_springCoefficients.bending_stiffness);
deformWorld->addForce(psb, springForce);
m_data->m_lf.push_back(springForce);
}

View File

@ -532,6 +532,7 @@ struct LoadSoftBodyArgs
double m_initialOrientation[4];
double m_springElasticStiffness;
double m_springDampingStiffness;
int m_dampAllDirections;
double m_springBendingStiffness;
double m_corotatedMu;
double m_corotatedLambda;

View File

@ -2038,7 +2038,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", "useMassSpring", "useBendingSprings", "useNeoHookean", "springElasticStiffness", "springDampingStiffness", "springBendingStiffness", "NeoHookeanMu", "NeoHookeanLambda", "NeoHookeanDamping", "frictionCoeff", "useFaceContact", "useSelfCollision", "repulsionStiffness", "physicsClientId", NULL};
static char* kwlist[] = {"fileName", "basePosition", "baseOrientation", "scale", "mass", "collisionMargin", "useMassSpring", "useBendingSprings", "useNeoHookean", "springElasticStiffness", "springDampingStiffness", "springDampingAllDirections", "springBendingStiffness", "NeoHookeanMu", "NeoHookeanLambda", "NeoHookeanDamping", "frictionCoeff", "useFaceContact", "useSelfCollision", "repulsionStiffness", "physicsClientId", NULL};
int bodyUniqueId = -1;
const char* fileName = "";
@ -2050,6 +2050,7 @@ static PyObject* pybullet_loadSoftBody(PyObject* self, PyObject* args, PyObject*
int useNeoHookean = 0;
double springElasticStiffness = 1;
double springDampingStiffness = 0.1;
int springDampingAllDirections = 0;
double springBendingStiffness = 0.1;
double NeoHookeanMu = 1;
double NeoHookeanLambda = 1;
@ -2068,7 +2069,7 @@ static PyObject* pybullet_loadSoftBody(PyObject* self, PyObject* args, PyObject*
PyObject* basePosObj = 0;
PyObject* baseOrnObj = 0;
if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|OOdddiiidddddddiidi", kwlist, &fileName, &basePosObj, &baseOrnObj, &scale, &mass, &collisionMargin, &useMassSpring, &useBendingSprings, &useNeoHookean, &springElasticStiffness, &springDampingStiffness, &springBendingStiffness, &NeoHookeanMu, &NeoHookeanLambda, &NeoHookeanDamping, &frictionCoeff, &useFaceContact, &useSelfCollision, &repulsionStiffness, &physicsClientId))
if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|OOdddiiiddidddddiidi", kwlist, &fileName, &basePosObj, &baseOrnObj, &scale, &mass, &collisionMargin, &useMassSpring, &useBendingSprings, &useNeoHookean, &springElasticStiffness, &springDampingStiffness, &springDampingAllDirections, &springBendingStiffness, &NeoHookeanMu, &NeoHookeanLambda, &NeoHookeanDamping, &frictionCoeff, &useFaceContact, &useSelfCollision, &repulsionStiffness, &physicsClientId))
{
return NULL;
}
@ -2123,7 +2124,7 @@ static PyObject* pybullet_loadSoftBody(PyObject* self, PyObject* args, PyObject*
}
if (useMassSpring)
{
b3LoadSoftBodyAddMassSpringForce(command, springElasticStiffness, springDampingStiffness);
b3LoadSoftBodyAddMassSpringForce(command, springElasticStiffness, springDampingStiffness, springDampingAllDirections);
b3LoadSoftBodyUseBendingSprings(command, useBendingSprings, springBendingStiffness);
}
if (useNeoHookean)