Triangle mesh body does not collide with static plane

karnivaurus
Posts: 9
Joined: Thu Nov 19, 2015 2:18 pm

Triangle mesh body does not collide with static plane

Post by karnivaurus »

I have written a simple demo where a triangle mesh, in the shape of a tetrahedron, falls onto a static plane. This is derived from a demo whereby a sphere falls onto the plane. In the case of the sphere, it falls with gravity and then hits the plane and comes to rest. However, with the mesh body, it falls with gravity but then passes through the plane and continues to fall. Why is my mesh body not hitting the plane?

Here is my entire code:

Code: Select all

#include <iostream>

#include "btBulletDynamicsCommon.h"

int main()
{
    // Initialisation
    btDefaultCollisionConfiguration* collision_configuration = new btDefaultCollisionConfiguration();
    btCollisionDispatcher* dispatcher = new btCollisionDispatcher(collision_configuration);
    btBroadphaseInterface* broadphase = new btDbvtBroadphase();
    btSequentialImpulseConstraintSolver* solver = new btSequentialImpulseConstraintSolver;
    btDiscreteDynamicsWorld* dynamics_world = new btDiscreteDynamicsWorld(dispatcher, broadphase, solver, collision_configuration);
    dynamics_world->setGravity(btVector3(0, -10, 0));

    // Static plane
    btCollisionShape* ground_collision_shape = new btStaticPlaneShape(btVector3(0, 1, 0), 0);
    btDefaultMotionState* ground_motion_state = new btDefaultMotionState(btTransform(btQuaternion(0, 0, 0, 1), btVector3(0, 0, 0)));
    btScalar ground_mass = 0;
    btRigidBody* ground_body = new btRigidBody(ground_mass, ground_motion_state, ground_collision_shape);
    dynamics_world->addRigidBody(ground_body);

    // Mesh
    btTriangleMesh* mesh = new btTriangleMesh();
    btVector3 v1(0, 0, 0);
    btVector3 v2(1, 0, 0);
    btVector3 v3(0.5, 1, 0);
    mesh->addTriangle(v1, v2, v3);
    v1 = btVector3(1, 0, 0);
    v2 = btVector3(0.5, 0, 1);
    v3 = btVector3(0.5, 0.866, 0);
    mesh->addTriangle(v1, v2, v3);
    v1 = btVector3(0.5, 0, 0.866);
    v2 = btVector3(0, 0, 0);
    v3 = btVector3(0.5, 0.866, 0);
    mesh->addTriangle(v1, v2, v3);
    v1 = btVector3(0, 0, 0);
    v2 = btVector3(1, 0, 0);
    v3 = btVector3(0.5, 0, 0.866);
    mesh->addTriangle(v1, v2, v3);
    btCollisionShape* mesh_collision_shape = new btBvhTriangleMeshShape(mesh, 1);
    btDefaultMotionState* mesh_motion_state = new btDefaultMotionState(btTransform(btQuaternion(0, 0, 0, 1), btVector3(0, 50, 0)));
    btScalar mesh_mass = 1;
    btVector3 mesh_inertia(0, 0, 0);
    mesh_collision_shape->calculateLocalInertia(mesh_mass, mesh_inertia);
    btRigidBody* mesh_body = new btRigidBody(mesh_mass, mesh_motion_state, mesh_collision_shape);
    dynamics_world->addRigidBody(mesh_body);

    // Simulation
    for (int i = 0; i < 300; i++)
    {
        dynamics_world->stepSimulation(1.f/60.f, 10);
        btTransform mesh_transform;
        mesh_body->getMotionState()->getWorldTransform(mesh_transform);
        std::cout <<  mesh_transform.getOrigin().getY() << std::endl;
    }

    return 0;
}
User avatar
Erwin Coumans
Site Admin
Posts: 4221
Joined: Sun Jun 26, 2005 6:43 pm
Location: California, USA

Re: Triangle mesh body does not collide with static plane

Post by Erwin Coumans »

There is only collision/contact information between btTriangleMesh/btBvhTriangleMeshShape and convex shapes or compound shapes,
there is no btBvhTriangleMeshShape versus btBvhTriangleMeshShape.

For a tetrahedron, you better just use a btConvexHullShape.

Otherwise, for more complex triangle meshes it is recommended to perform convex decomposition (using HACD or VHACD or manually).
If that is not an option, you could try adding the triangles individually to a btCompoundShape. Fatten the triangles a bit, by using some positive collision margin.

Note that Bullet (and most other collision libraries) only implement local penetration depth information, which doesn't work too well, unless you use fat triangles or convex hulls with sufficient volume to avoid degeneracies.
karnivaurus
Posts: 9
Joined: Thu Nov 19, 2015 2:18 pm

Re: Triangle mesh body does not collide with static plane

Post by karnivaurus »

Thanks for your help. According to this link, http://bulletphysics.org/Bullet/phpBB3/ ... w=previous, then I can use btGimpactMeshShape for triangle meshes with collision detections between them. Is that correct?

I tried updating my code using btGimpactMeshShape instead of btBvhTriangleMeshShape, but then in this case, the tetrahedron does not fall at all. It just remains at y = 50, even though the only change to my code is the collision shape type. Why is this...?