Now, if I set the world position of the plane to be at (0, 0, 0), and the cube to be at (0, 0.3, 0), then the cube falls onto the plane and rests there, as would be expected. However, I am getting some strange behaviour when I change the position of the plane, even slightly.
For example, if I set the world position of the plane to be at (-0.1, 0, -0.1,), with the cube still at (0, 0.3, 0), then the cube falls right through the plane, and there is no collision. But the plane is still directly beneath the cube as it falls, and so a collision should be detected. In fact, if I set the plane to be positioned at anything other than (0, 0, 0), then there is no collision.
The plane's position is set in the code:
Code: Select all
btDefaultMotionState* plane_start_motion_state = new btDefaultMotionState(btTransform(btQuaternion(0, 0, 0, 1), btVector3(0, 0, 0)));
Code: Select all
btDefaultMotionState* plane_start_motion_state = new btDefaultMotionState(btTransform(btQuaternion(0, 0, 0, 1), btVector3(dx, 0, dz)));
Any ideas on what is causing this?
Thanks!
The minimum code to repeat this is below:
Code: Select all
#include <iostream>
#include <Eigen/Eigen>
#include "btBulletDynamicsCommon.h"
#include "BulletCollision/Gimpact/btGImpactShape.h"
#include "BulletCollision/Gimpact/btGImpactCollisionAlgorithm.h"
int main(int argc, char** argv)
{
// Set up Bullet
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, -9.81, 0));
// Make the plane
float plane_dx = 1.0;
float plane_dy = 0.1;
float plane_dz = 1.0;
int plane_num_vertices = 8;
int plane_num_triangles = 12;
int plane_num_indices = plane_num_triangles * 3;
std::vector<Eigen::Vector3f> plane_vertex_positions;
std::vector<int> plane_vertex_indices;
plane_vertex_positions.resize(plane_num_vertices);
plane_vertex_positions[0] << 0, 0, 0;
plane_vertex_positions[1] << 0, -plane_dy, 0;
plane_vertex_positions[2] << 0, -plane_dy, plane_dz;
plane_vertex_positions[3] << 0, 0, plane_dz;
plane_vertex_positions[4] << plane_dx, 0, 0;
plane_vertex_positions[5] << plane_dx, -plane_dy, 0;
plane_vertex_positions[6] << plane_dx, -plane_dy, plane_dz;
plane_vertex_positions[7] << plane_dx, 0, plane_dz;
plane_vertex_indices.resize(plane_num_indices);
plane_vertex_indices[0] = 0;
plane_vertex_indices[1] = 3;
plane_vertex_indices[2] = 2;
plane_vertex_indices[3] = 2;
plane_vertex_indices[4] = 1;
plane_vertex_indices[5] = 0;
plane_vertex_indices[6] = 4;
plane_vertex_indices[7] = 0;
plane_vertex_indices[8] = 1;
plane_vertex_indices[9] = 1;
plane_vertex_indices[10] = 5;
plane_vertex_indices[11] = 4;
plane_vertex_indices[12] = 7;
plane_vertex_indices[13] = 4;
plane_vertex_indices[14] = 5;
plane_vertex_indices[15] = 5;
plane_vertex_indices[16] = 6;
plane_vertex_indices[17] = 7;
plane_vertex_indices[18] = 3;
plane_vertex_indices[19] = 7;
plane_vertex_indices[20] = 6;
plane_vertex_indices[21] = 6;
plane_vertex_indices[22] = 2;
plane_vertex_indices[23] = 3;
plane_vertex_indices[24] = 2;
plane_vertex_indices[25] = 6;
plane_vertex_indices[26] = 5;
plane_vertex_indices[27] = 5;
plane_vertex_indices[28] = 1;
plane_vertex_indices[29] = 2;
plane_vertex_indices[30] = 0;
plane_vertex_indices[31] = 4;
plane_vertex_indices[32] = 7;
plane_vertex_indices[33] = 7;
plane_vertex_indices[34] = 3;
plane_vertex_indices[35] = 0;
btTriangleIndexVertexArray* plane_mesh = new btTriangleIndexVertexArray(plane_num_triangles, plane_vertex_indices.data(), 0, plane_num_vertices, (btScalar*)plane_vertex_positions.data(), 0);
btConvexTriangleMeshShape* plane_shape = new btConvexTriangleMeshShape(plane_mesh);
plane_shape->setLocalScaling(btVector3(1., 1., 1.));
plane_shape->setMargin(0.04f);
btVector3 plane_inertia(0, 0, 0);
btScalar plane_mass(0.0f);
plane_shape->calculateLocalInertia(plane_mass, plane_inertia);
btDefaultMotionState* plane_start_motion_state = new btDefaultMotionState(btTransform(btQuaternion(0, 0, 0, 1), btVector3(0, 0, 0)));
btRigidBody* plane = new btRigidBody(plane_mass, plane_start_motion_state, plane_shape, plane_inertia);
plane->setFriction(0.5);
plane->setRestitution(0.5);
dynamics_world->addRigidBody(plane);
// Make the Cube
float cube_dx = 0.1;
float cube_dy = 0.1;
float cube_dz = 0.1;
int cube_num_vertices = 8;
int cube_num_triangles = 12;
int cube_num_indices = cube_num_triangles * 3;
std::vector<Eigen::Vector3f> cube_vertex_positions;
std::vector<int> cube_vertex_indices;
cube_vertex_positions.resize(cube_num_vertices);
cube_vertex_positions[0] << 0, 0, 0;
cube_vertex_positions[1] << 0, cube_dy, 0;
cube_vertex_positions[2] << 0, cube_dy, cube_dz;
cube_vertex_positions[3] << 0, 0, cube_dz;
cube_vertex_positions[4] << cube_dx, 0, 0;
cube_vertex_positions[5] << cube_dx, cube_dy, 0;
cube_vertex_positions[6] << cube_dx, cube_dy, cube_dz;
cube_vertex_positions[7] << cube_dx, 0, cube_dz;
cube_vertex_indices.resize(cube_num_indices);
cube_vertex_indices[0] = 0;
cube_vertex_indices[1] = 3;
cube_vertex_indices[2] = 2;
cube_vertex_indices[3] = 2;
cube_vertex_indices[4] = 1;
cube_vertex_indices[5] = 0;
cube_vertex_indices[6] = 4;
cube_vertex_indices[7] = 0;
cube_vertex_indices[8] = 1;
cube_vertex_indices[9] = 1;
cube_vertex_indices[10] = 5;
cube_vertex_indices[11] = 4;
cube_vertex_indices[12] = 7;
cube_vertex_indices[13] = 4;
cube_vertex_indices[14] = 5;
cube_vertex_indices[15] = 5;
cube_vertex_indices[16] = 6;
cube_vertex_indices[17] = 7;
cube_vertex_indices[18] = 3;
cube_vertex_indices[19] = 7;
cube_vertex_indices[20] = 6;
cube_vertex_indices[21] = 6;
cube_vertex_indices[22] = 2;
cube_vertex_indices[23] = 3;
cube_vertex_indices[24] = 2;
cube_vertex_indices[25] = 6;
cube_vertex_indices[26] = 5;
cube_vertex_indices[27] = 5;
cube_vertex_indices[28] = 1;
cube_vertex_indices[29] = 2;
cube_vertex_indices[30] = 0;
cube_vertex_indices[31] = 4;
cube_vertex_indices[32] = 7;
cube_vertex_indices[33] = 7;
cube_vertex_indices[34] = 3;
cube_vertex_indices[35] = 0;
btTriangleIndexVertexArray* cube_mesh = new btTriangleIndexVertexArray(cube_num_triangles, cube_vertex_indices.data(), 0, cube_num_vertices, (btScalar*)cube_vertex_positions.data(), 0);
btConvexTriangleMeshShape* cube_shape = new btConvexTriangleMeshShape(cube_mesh);
cube_shape->setLocalScaling(btVector3(1., 1., 1.));
cube_shape->setMargin(0.04f);
btVector3 cube_inertia(0, 0, 0);
btScalar cube_mass(1.0f);
cube_shape->calculateLocalInertia(cube_mass, cube_inertia);
btDefaultMotionState* cube_start_motion_state = new btDefaultMotionState(btTransform(btQuaternion(0, 0, 0, 1), btVector3(0, 3, 0)));
btRigidBody* cube = new btRigidBody(cube_mass, cube_start_motion_state, cube_shape, cube_inertia);
cube->setFriction(0.5);
cube->setRestitution(0.5);
dynamics_world->addRigidBody(cube);
float t = 0.00001f;
for (int i = 0; i < 10000000; i++)
{
dynamics_world->stepSimulation(t, 10, t / 10.0f);
btTransform cube_transform;
cube->getMotionState()->getWorldTransform(cube_transform);
std::cout << "Cube position = " << cube_transform.getOrigin().getY() << std::endl;
}
}