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

@@ -571,6 +571,24 @@ bool UrdfParser::parseCollision(UrdfCollision& collision, XMLElement* config, Er
return false;
}
{
const char* group_char = config->Attribute("group");
if (group_char)
{
collision.m_flags |= URDF_HAS_COLLISION_GROUP;
collision.m_collisionGroup = urdfLexicalCast<int>(group_char);
}
}
{
const char* mask_char = config->Attribute("mask");
if (mask_char)
{
collision.m_flags |= URDF_HAS_COLLISION_MASK;
collision.m_collisionMask = urdfLexicalCast<int>(mask_char);
}
}
const char *name_char = config->Attribute("name");
if (name_char)