mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-13 13:20:07 +00:00
set appropriate repulsion stiffness for pybullet torus demo
This commit is contained in:
parent
38657ebdfd
commit
5f1260199a
@ -6,6 +6,7 @@
|
||||
<inertia ixx="0.0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" />
|
||||
</inertial>
|
||||
<collision_margin value="0.006"/>
|
||||
<repulsion_stiffness value="50.0"/>
|
||||
<friction value= "0.5"/>
|
||||
<neohookean mu= "60" lambda= "200" damping= "0.01" />
|
||||
<visual filename="torus.vtk"/>
|
||||
|
@ -648,7 +648,7 @@ extern "C"
|
||||
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);
|
||||
B3_SHARED_API int b3LoadSoftBodyRepulsionStiffness(b3SharedMemoryCommandHandle commandHandle, double stiffness);
|
||||
B3_SHARED_API int b3LoadSoftBodySetRepulsionStiffness(b3SharedMemoryCommandHandle commandHandle, double stiffness);
|
||||
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, double bendingStiffness);
|
||||
|
@ -11,7 +11,7 @@ planeId = p.loadURDF("plane.urdf", [0,0,-2])
|
||||
|
||||
boxId = p.loadURDF("cube.urdf", [0,3,2],useMaximalCoordinates = True)
|
||||
|
||||
bunnyId = p.loadSoftBody("torus.vtk", useNeoHookean = 1, NeoHookeanMu = 60, NeoHookeanLambda = 200, NeoHookeanDamping = 0.01, useSelfCollision = 1, frictionCoeff = 0.5)
|
||||
bunnyId = p.loadSoftBody("torus.vtk", mass = 1, useNeoHookean = 1, NeoHookeanMu = 60, NeoHookeanLambda = 200, NeoHookeanDamping = 0.01, collisionMargin = 0.006, useSelfCollision = 1, frictionCoeff = 0.5, repulsionStiffness = 50)
|
||||
|
||||
bunny2 = p.loadURDF("torus_deform.urdf", [0,1,0], flags=p.URDF_USE_SELF_COLLISION)
|
||||
|
||||
@ -20,4 +20,3 @@ p.setRealTimeSimulation(1)
|
||||
|
||||
while p.isConnected():
|
||||
p.setGravity(0,0,-10)
|
||||
sleep(1./240.)
|
||||
|
@ -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", "physicsClientId", "useMassSpring", "useBendingSprings", "useNeoHookean", "springElasticStiffness", "springDampingStiffness", "springBendingStiffness", "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", "repulsionStiffness", NULL};
|
||||
|
||||
int bodyUniqueId = -1;
|
||||
const char* fileName = "";
|
||||
@ -2057,6 +2057,7 @@ static PyObject* pybullet_loadSoftBody(PyObject* self, PyObject* args, PyObject*
|
||||
double frictionCoeff = 0;
|
||||
int useFaceContact = 0;
|
||||
int useSelfCollision = 0;
|
||||
double repulsionStiffness = 0.5;
|
||||
|
||||
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
@ -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|OOdddiiiidddddddii", kwlist, &fileName, &basePosObj, &baseOrnObj, &scale, &mass, &collisionMargin, &physicsClientId, &useMassSpring, &useBendingSprings, &useNeoHookean, &springElasticStiffness, &springDampingStiffness, &springBendingStiffness, &NeoHookeanMu, &NeoHookeanLambda, &NeoHookeanDamping, &frictionCoeff, &useFaceContact, &useSelfCollision))
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|OOdddiiiidddddddiid", kwlist, &fileName, &basePosObj, &baseOrnObj, &scale, &mass, &collisionMargin, &physicsClientId, &useMassSpring, &useBendingSprings, &useNeoHookean, &springElasticStiffness, &springDampingStiffness, &springBendingStiffness, &NeoHookeanMu, &NeoHookeanLambda, &NeoHookeanDamping, &frictionCoeff, &useFaceContact, &useSelfCollision, &repulsionStiffness))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
@ -2134,6 +2135,10 @@ static PyObject* pybullet_loadSoftBody(PyObject* self, PyObject* args, PyObject*
|
||||
{
|
||||
b3LoadSoftBodySetSelfCollision(command, useSelfCollision);
|
||||
}
|
||||
if (repulsionStiffness > 0)
|
||||
{
|
||||
b3LoadSoftBodySetRepulsionStiffness(command, repulsionStiffness);
|
||||
}
|
||||
b3LoadSoftBodySetFrictionCoefficient(command, frictionCoeff);
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
|
@ -8,6 +8,7 @@
|
||||
#include "LinearMath/btConvexHullComputer.cpp"
|
||||
#include "LinearMath/btQuickprof.cpp"
|
||||
#include "LinearMath/btThreads.cpp"
|
||||
#include "LinearMath/btReducedVector.cpp"
|
||||
#include "LinearMath/TaskScheduler/btTaskScheduler.cpp"
|
||||
#include "LinearMath/TaskScheduler/btThreadSupportPosix.cpp"
|
||||
#include "LinearMath/TaskScheduler/btThreadSupportWin32.cpp"
|
||||
|
Loading…
Reference in New Issue
Block a user