add python binding to allow loading deformable objects

This commit is contained in:
Xuchen Han
2019-11-15 21:25:11 -08:00
parent 655981c6ad
commit 22fb2cfb5e
6 changed files with 59 additions and 9 deletions

View File

@@ -386,12 +386,12 @@ B3_SHARED_API int b3LoadSoftBodySetCollisionHardness(b3SharedMemoryCommandHandle
return 0;
}
B3_SHARED_API int b3LoadSoftBodySetSelfCollision(b3SharedMemoryCommandHandle commandHandle, int useSelfCollision)
B3_SHARED_API int b3LoadSoftBodyUseSelfCollision(b3SharedMemoryCommandHandle commandHandle, int useSelfCollision)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
b3Assert(command->m_type == CMD_LOAD_SOFT_BODY);
command->m_loadSoftBodyArguments.m_useSelfCollision = useSelfCollision;
command->m_updateFlags |= LOAD_SOFT_BODY_SET_SELF_COLLISION;
command->m_updateFlags |= LOAD_SOFT_BODY_USE_SELF_COLLISION;
return 0;
}
@@ -413,6 +413,15 @@ B3_SHARED_API int b3LoadSoftBodyUseBendingSprings(b3SharedMemoryCommandHandle co
return 0;
}
B3_SHARED_API int b3LoadSoftBodyUseFaceContact(b3SharedMemoryCommandHandle commandHandle, int useFaceContact)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
b3Assert(command->m_type == CMD_LOAD_SOFT_BODY);
command->m_loadSoftBodyArguments.m_useFaceContact = useFaceContact;
command->m_updateFlags |= LOAD_SOFT_BODY_USE_FACE_CONTACT;
return 0;
}
B3_SHARED_API b3SharedMemoryCommandHandle b3LoadUrdfCommandInit(b3PhysicsClientHandle physClient, const char* urdfFileName)
{
PhysicsClient* cl = (PhysicsClient*)physClient;

View File

@@ -638,7 +638,8 @@ extern "C"
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 b3LoadSoftBodySetCollisionHardness(b3SharedMemoryCommandHandle commandHandle, double collisionHardness);
B3_SHARED_API int b3LoadSoftBodySetSelfCollision(b3SharedMemoryCommandHandle commandHandle, int useSelfCollision);
B3_SHARED_API int b3LoadSoftBodyUseSelfCollision(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);

View File

@@ -8250,7 +8250,7 @@ bool PhysicsServerCommandProcessor::processLoadSoftBodyCommand(const struct Shar
psb->setCollisionFlags(0);
psb->setTotalMass(mass);
bool use_self_collision = false;
if (clientCmd.m_updateFlags & LOAD_SOFT_BODY_SET_SELF_COLLISION)
if (clientCmd.m_updateFlags & LOAD_SOFT_BODY_USE_SELF_COLLISION)
{
use_self_collision = loadSoftBodyArgs.m_useSelfCollision;
}
@@ -13446,7 +13446,6 @@ void PhysicsServerCommandProcessor::resetSimulation(int flags)
softWorld->getWorldInfo().m_sparsesdf.Reset();
}
}
}
#endif
if (m_data && m_data->m_guiHelper)

View File

@@ -502,7 +502,8 @@ enum EnumLoadSoftBodyUpdateFlags
LOAD_SOFT_BODY_SET_FRICTION_COEFFICIENT = 1<<10,
LOAD_SOFT_BODY_ADD_BENDING_SPRINGS = 1<<11,
LOAD_SOFT_BODY_ADD_NEOHOOKEAN_FORCE = 1<<12,
LOAD_SOFT_BODY_SET_SELF_COLLISION = 1<<13,
LOAD_SOFT_BODY_USE_SELF_COLLISION = 1<<13,
LOAD_SOFT_BODY_USE_FACE_CONTACT = 1<<14,
};
enum EnumSimParamInternalSimFlags
@@ -525,13 +526,14 @@ struct LoadSoftBodyArgs
double m_springDampingStiffness;
double m_corotatedMu;
double m_corotatedLambda;
bool m_useBendingSprings;
int m_useBendingSprings;
double m_collisionHardness;
double m_useSelfCollision;
double m_frictionCoeff;
double m_NeoHookeanMu;
double m_NeoHookeanLambda;
double m_NeoHookeanDamping;
int m_useFaceContact;
};
struct b3LoadSoftBodyResultArgs