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:
erwincoumans
2018-09-12 19:30:49 -07:00
parent bf3399d0e3
commit 9553892770
20 changed files with 675 additions and 89 deletions

View File

@@ -699,6 +699,23 @@ struct CalculateMassMatrixResultArgs
int m_dofCount;
};
enum b3EnumCollisionFilterFlags
{
B3_COLLISION_FILTER_PAIR=1,
B3_COLLISION_FILTER_GROUP_MASK=2,
};
struct b3CollisionFilterArgs
{
int m_bodyUniqueIdA;
int m_bodyUniqueIdB;
int m_linkIndexA;
int m_linkIndexB;
int m_enableCollision;
int m_collisionFilterGroup;
int m_collisionFilterMask;
};
struct CalculateInverseKinematicsArgs
{
int m_bodyUniqueId;
@@ -1087,6 +1104,7 @@ struct SharedMemoryCommand
struct UserDataRequestArgs m_userDataRequestArgs;
struct AddUserDataRequestArgs m_addUserDataRequestArgs;
struct UserDataRequestArgs m_removeUserDataRequestArgs;
struct b3CollisionFilterArgs m_collisionFilterArgs;
};
};