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

@@ -0,0 +1,17 @@
import pybullet as p
import time
p.connect(p.GUI)
planeId = p.loadURDF("plane.urdf", useMaximalCoordinates=False)
cubeId = p.loadURDF("cube_collisionfilter.urdf", [0,0,3], useMaximalCoordinates=False)
collisionFilterGroup = 0
collisionFilterMask = 0
p.setCollisionFilterGroupMask(cubeId,-1,collisionFilterGroup,collisionFilterMask)
enableCollision = 1
p.setCollisionFilterPair(planeId, cubeId,-1,-1,enableCollision )
p.setRealTimeSimulation(1)
p.setGravity(0,0,-10)
while (p.isConnected()):
time.sleep(1)