PyBullet / BulletRobotics:
Implement collisionFilterPlugin, use setCollisionFilterPair to enable or disable collision detection between specific pairs of objects. Also, expose setCollisionFilterGroupMask as PyBullet API and in urdf using the tag <collision group="1" mask="2"/>. See examples/pybullet/examples/collisionFilter.py for an example. PyBullet default: Lower the warmstarting factor, for maximal coordinates rigid bodies for more stable simulation. Add btCollisionWorld::refreshBroadphaseProxy to easier recreate the broadphase proxy without adding/removing objects to the world.
This commit is contained in:
33
examples/SharedMemory/plugins/b3PluginCollisionInterface.h
Normal file
33
examples/SharedMemory/plugins/b3PluginCollisionInterface.h
Normal file
@@ -0,0 +1,33 @@
|
||||
#ifndef B3_PLUGIN_COLLISION_INTERFACE_H
|
||||
#define B3_PLUGIN_COLLISION_INTERFACE_H
|
||||
|
||||
enum b3PluginCollisionFilterModes
|
||||
{
|
||||
B3_FILTER_GROUPAMASKB_AND_GROUPBMASKA=0,
|
||||
B3_FILTER_GROUPAMASKB_OR_GROUPBMASKA
|
||||
};
|
||||
|
||||
struct b3PluginCollisionInterface
|
||||
{
|
||||
virtual void setBroadphaseCollisionFilter(
|
||||
int objectUniqueIdA, int objectUniqueIdB,
|
||||
int linkIndexA, int linkIndexB,
|
||||
bool enableCollision)=0;
|
||||
|
||||
virtual void removeBroadphaseCollisionFilter(
|
||||
int objectUniqueIdA, int objectUniqueIdB,
|
||||
int linkIndexA, int linkIndexB)=0;
|
||||
|
||||
virtual int getNumRules() const = 0;
|
||||
|
||||
virtual void resetAll()=0;
|
||||
|
||||
virtual int needsBroadphaseCollision(int objectUniqueIdA, int linkIndexA,
|
||||
int collisionFilterGroupA,int collisionFilterMaskA,
|
||||
int objectUniqueIdB, int linkIndexB,
|
||||
int collisionFilterGroupB,int collisionFilterMaskB,
|
||||
int filterMode
|
||||
)=0;
|
||||
};
|
||||
|
||||
#endif //B3_PLUGIN_COLLISION_INTERFACE_H
|
||||
Reference in New Issue
Block a user