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

@@ -1405,7 +1405,31 @@ int BulletURDFImporter::getAllocatedTexture(int index) const
return m_data->m_allocatedTextures[index];
}
int BulletURDFImporter::getCollisionGroupAndMask(int linkIndex, int& colGroup, int& colMask) const
{
int result = 0;
UrdfLink* const* linkPtr = m_data->m_urdfParser.getModel().m_links.getAtIndex(linkIndex);
btAssert(linkPtr);
if (linkPtr)
{
UrdfLink* link = *linkPtr;
for (int v=0;v<link->m_collisionArray.size();v++)
{
const UrdfCollision& col = link->m_collisionArray[v];
if (col.m_flags & URDF_HAS_COLLISION_GROUP)
{
colGroup = col.m_collisionGroup;
result |= URDF_HAS_COLLISION_GROUP;
}
if (col.m_flags & URDF_HAS_COLLISION_MASK)
{
colMask = col.m_collisionMask;
result |= URDF_HAS_COLLISION_MASK;
}
}
}
return result;
}
class btCompoundShape* BulletURDFImporter::convertLinkCollisionShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame) const
{