PyBullet: expose internal edge utility, to adjust edge normals to prevent object penetrating along triangle edges of concave triangle meshes
(due to local convex-triangle collisions causing opposite contact normals, use the pre-computed edge normal) PyBullet: expose experimental continuous collision detection for maximal coordinate rigid bodies, to prevent tunneling.
This commit is contained in:
@@ -2,6 +2,9 @@
|
||||
#include "LinearMath/btTransform.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h"
|
||||
#include "BulletCollision/CollisionShapes/btCompoundShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btBvhTriangleMeshShape.h"
|
||||
|
||||
|
||||
#include "BulletDynamics/Dynamics/btRigidBody.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.h"
|
||||
@@ -502,6 +505,15 @@ void ConvertURDF2BulletInternal(
|
||||
|
||||
col->setCollisionShape(compoundShape);
|
||||
|
||||
if (compoundShape->getShapeType() == TRIANGLE_MESH_SHAPE_PROXYTYPE)
|
||||
{
|
||||
btBvhTriangleMeshShape* trimeshShape = (btBvhTriangleMeshShape*)compoundShape;
|
||||
if (trimeshShape->getTriangleInfoMap())
|
||||
{
|
||||
col->setCollisionFlags(col->getCollisionFlags() | btCollisionObject::CF_CUSTOM_MATERIAL_CALLBACK);
|
||||
}
|
||||
}
|
||||
|
||||
btTransform tr;
|
||||
tr.setIdentity();
|
||||
tr = linkTransformInWorldSpace;
|
||||
|
||||
Reference in New Issue
Block a user