Rigidbody from btBvhTriangleMeshShape doesn't collide with Others

Post Reply
kcjsend2
Posts: 15
Joined: Wed Jun 30, 2021 9:10 am

Rigidbody from btBvhTriangleMeshShape doesn't collide with Others

Post by kcjsend2 »

hi.

What I try to do is simple. make few btBvhTriangleMeshShape, and gather it by btCompoundShape.
TriangleMeshShape's AABB values seems correct to me, so I think vertices and Indices data for shapes are correct either.

this codes show how I import mesh datas from obj wavefront file, and make it collision shape.

Code: Select all

std::vector<std::shared_ptr<Mesh>> GameObject::LoadModel(
	ID3D12Device* device, 
	ID3D12GraphicsCommandList* cmdList, 
	const std::wstring& path,
	const bool& makeRigidbody)
{
	std::ifstream in_file{ path, std::ios::binary };
	assert(in_file.is_open(), L"No such file in path [" + path + L"]");

	std::vector<XMFLOAT3> positions;
	std::vector<XMFLOAT3> normals;
	std::vector<XMFLOAT2> texcoords;
	std::unordered_map<std::string, MatInfo> mats;
	std::shared_ptr<Mesh> new_mesh;

	std::string info;
	while (std::getline(in_file, info))
	{
		std::stringstream ss(info);
		std::string type;

		ss >> type;

		if (type == "mtllib")
		{
			std::string mtlname;
			ss >> mtlname;

			std::wstring mtl_path = L"";
			std::wstring::size_type n = path.find('\\');
			if (n != std::wstring::npos)
				mtl_path = path.substr(0, n + 1);

			mtl_path += std::wstring(mtlname.begin(), mtlname.end());

			LoadMaterial(device, cmdList, mats, mtl_path);
		}
		else if (type == "v")
		{
			XMFLOAT3 pos;
			ss >> pos.x >> pos.y >> pos.z;
			pos.z *= -1.0f;
			positions.push_back(pos);
		}
		else if (type == "vt")
		{
			XMFLOAT2 tex;
			ss >> tex.x >> tex.y;
			//tex.y = 1.0f - tex.y;
			texcoords.push_back(tex);
		}
		else if (type == "vn")
		{
			XMFLOAT3 norm;
			ss >> norm.x >> norm.y >> norm.z;
			norm.z *= -1.0f;
			normals.push_back(norm);
		}
		else if (type == "usemtl")
		{
			std::string mtl_name;
			ss >> mtl_name;

			new_mesh = std::make_shared<Mesh>(mtl_name);
			new_mesh->LoadMesh(
				device, cmdList, in_file, 
				positions, normals, texcoords, mats[mtl_name], makeRigidbody);
			mMeshes.push_back(new_mesh);
		}
	}

	const auto& [min_x, max_x] = std::minmax_element(positions.begin(), positions.end(), 
		[](const XMFLOAT3& a, const XMFLOAT3& b) { return (a.x < b.x); });
	const auto& [min_y, max_y] = std::minmax_element(positions.begin(), positions.end(),
		[](const XMFLOAT3& a, const XMFLOAT3& b) {return (a.y < b.y); });
	const auto& [min_z, max_z] = std::minmax_element(positions.begin(), positions.end(),
		[](const XMFLOAT3& a, const XMFLOAT3& b) {return (a.z < b.z); });

	mOOBB.Center = { (min_x->x + max_x->x) / 2, (min_y->y + max_y->y) / 2, (min_z->z + max_z->z) / 2 };
	mOOBB.Extents = { (max_x->x - min_x->x) / 2, (max_y->y - min_y->y) / 2, (max_z->z - min_z->z) / 2 };

	return mMeshes;
}


void Mesh::LoadMesh(
	ID3D12Device* device, 
	ID3D12GraphicsCommandList* cmdList,
	std::ifstream& file,
	const std::vector<XMFLOAT3>& positions,
	const std::vector<XMFLOAT3>& normals,
	const std::vector<XMFLOAT2>& texcoords,
	const MatInfo& mat,
	const bool& makeRigidbody)
{
	mMaterial = mat;

	struct UINT3
	{
		UINT vertIndex;
		UINT normIndex;
		UINT texIndex;
	};
	std::vector<std::vector<UINT3>> temp_indices;

	int last_pos = 0;
	std::string info;
	while (std::getline(file, info))
	{		
		std::stringstream ss(info);
		std::string type;

		ss >> type;

		if (type == "f")
		{
			char ignore[2];
			UINT v, vt, vn;

			temp_indices.push_back({});
			while (ss >> v >> ignore[0] >> vt >> ignore[1] >> vn)
			{
				temp_indices.back().push_back({ v - 1, vn - 1, vt - 1 });
			}
			last_pos = (int)file.tellg();
		}
		else if (type == "usemtl") 
		{
			file.seekg(last_pos);
			break;
		}
	}

	std::vector<Vertex> vertices;
	std::vector<UINT> indices;
	UINT k = 0;
	for (const std::vector<UINT3>& curr_face : temp_indices)
	{
		for (int i = 0; i < curr_face.size(); i++)
		{
			Vertex v;
			v.Position = positions[curr_face[i].vertIndex];
			v.Normal = normals[curr_face[i].normIndex];
			v.TexCoord = texcoords[curr_face[i].texIndex];
			v.TexCoord.x /= mat.TexScale.x;
			v.TexCoord.x += mat.TexOffset.x;
			v.TexCoord.y /= mat.TexScale.y;
			v.TexCoord.y += mat.TexOffset.y;
			v.TexCoord.y = 1.0f - v.TexCoord.y;
			
			vertices.push_back(v);

			if (i > 0 && indices.size() % 3 == 0)
			{
				indices.push_back(*(indices.end() - 3));
				indices.push_back(*(indices.end() - 2));
			}
			indices.push_back(k++);
		}
	}

	const auto& [min_x, max_x] = std::minmax_element(positions.begin(), positions.end(),
		[](const XMFLOAT3& a, const XMFLOAT3& b) { return (a.x < b.x); });
	const auto& [min_y, max_y] = std::minmax_element(positions.begin(), positions.end(),
		[](const XMFLOAT3& a, const XMFLOAT3& b) {return (a.y < b.y); });
	const auto& [min_z, max_z] = std::minmax_element(positions.begin(), positions.end(),
		[](const XMFLOAT3& a, const XMFLOAT3& b) {return (a.z < b.z); });

	mOOBB.Center = { (min_x->x + max_x->x) / 2, (min_y->y + max_y->y) / 2, (min_z->z + max_z->z) / 2 };
	mOOBB.Extents = { (max_x->x - min_x->x) / 2, (max_y->y - min_y->y) / 2, (max_z->z - min_z->z) / 2 };

	if(makeRigidbody)
		CreateRigidBody(vertices, indices);

	std::reverse(indices.begin(), indices.end());
	Mesh::CreateResourceInfo(device, cmdList, sizeof(Vertex), sizeof(UINT),
		D3D_PRIMITIVE_TOPOLOGY_TRIANGLELIST,
		vertices.data(), (UINT)vertices.size(), indices.data(), (UINT)indices.size());
}

void Mesh::CreateRigidBody(const std::vector<Vertex>& targetVertices, const std::vector<UINT>& targetIndices)
{
	mTriangleVertexArray = new btTriangleIndexVertexArray();

	btIndexedMesh tempMesh;
	mTriangleVertexArray->addIndexedMesh(tempMesh, PHY_FLOAT);

	btIndexedMesh& mesh = mTriangleVertexArray->getIndexedMeshArray()[0];

	const int32_t VERTICES_PER_TRIANGLE = 3;
	size_t numIndices = targetIndices.size();
	mesh.m_numTriangles = numIndices / VERTICES_PER_TRIANGLE;

	if (numIndices < std::numeric_limits<int16_t>::max())
	{
		mesh.m_triangleIndexBase = new unsigned char[sizeof(int16_t) * (size_t)numIndices];
		mesh.m_indexType = PHY_SHORT;
		mesh.m_triangleIndexStride = VERTICES_PER_TRIANGLE * sizeof(int16_t);
	}
	else
	{
		mesh.m_triangleIndexBase = new unsigned char[sizeof(int32_t) * (size_t)numIndices];
		mesh.m_indexType = PHY_INTEGER;
		mesh.m_triangleIndexStride = VERTICES_PER_TRIANGLE * sizeof(int32_t);
	}

	mesh.m_numVertices = targetVertices.size();
	mesh.m_vertexBase = new unsigned char[VERTICES_PER_TRIANGLE * sizeof(btScalar) * (size_t)mesh.m_numVertices];
	mesh.m_vertexStride = VERTICES_PER_TRIANGLE * sizeof(btScalar);

	btScalar* vertexData = static_cast<btScalar*>((void*)(mesh.m_vertexBase));
	for (int32_t i = 0; i < mesh.m_numVertices; ++i)
	{
		int32_t j = i * VERTICES_PER_TRIANGLE;
		const XMFLOAT3& point = targetVertices[i].Position;
		vertexData[j] = point.x;
		vertexData[j + 1] = point.y;
		vertexData[j + 2] = point.z;
	}

	if (numIndices < std::numeric_limits<int16_t>::max())
	{
		int16_t* indices = static_cast<int16_t*>((void*)(mesh.m_triangleIndexBase));

		for (int32_t i = 0; i < numIndices; ++i) {
			indices[i] = (int16_t)targetIndices[i];
		}
	}
	else
	{
		int32_t* indices = static_cast<int32_t*>((void*)(mesh.m_triangleIndexBase));

		for (int32_t i = 0; i < numIndices; ++i)
		{
			indices[i] = targetIndices[i];
		}
	}

	const bool USE_QUANTIZED_AABB_COMPRESSION = true;
	mMeshShape = std::make_shared<btBvhTriangleMeshShape>(mTriangleVertexArray, USE_QUANTIZED_AABB_COMPRESSION);
}


void PhysicsPlayer::BuildRigidBody(std::shared_ptr<BulletWrapper> physics)
{
	auto dynamicsWorld = physics->GetDynamicsWorld();

	mOOBB.Extents = { 10.0f, 4.0f, 14.0f }; // this value is for wheel

	XMFLOAT3 vehicleExtents = mOOBB.Extents;
	XMFLOAT3 wheelExtents = mWheel[0]->GetBoundingBox().Extents;

	btCompoundShape* chassisShape = new btCompoundShape();

	for (int i = 0; i < mMeshes.size(); ++i)
	{
		btTransform LocalTransform;
		LocalTransform.setIdentity();
		LocalTransform.setOrigin(btVector3(0, 0, 0));

		chassisShape->addChildShape(LocalTransform, mMeshes[i]->GetMeshShape().get());
	}

	btTransform btCarTransform;
	btCarTransform.setIdentity();
	btCarTransform.setOrigin(btVector3(mPosition.x, mPosition.y, mPosition.z));

	mBtRigidBody = physics->CreateRigidBody(1000.0f, btCarTransform, chassisShape);
	mVehicleRayCaster = std::make_shared<btDefaultVehicleRaycaster>(dynamicsWorld.get());
	mVehicle = std::make_shared<btRaycastVehicle>(mTuning, mBtRigidBody, mVehicleRayCaster.get());

	mBtRigidBody->setActivationState(DISABLE_DEACTIVATION);
	dynamicsWorld->addVehicle(mVehicle.get());

	mVehicle->setCoordinateSystem(0, 1, 2);

	btVector3 wheelDirectionCS0(0, -1, 0);
	btVector3 wheelAxleCS(-1, 0, 0);

	float wheelWidth = wheelExtents.x;
	float wheelRadius = wheelExtents.z;
	float wheelFriction = 26.0f;
	float suspensionStiffness = 20.f;
	float suspensionDamping = 2.3f;
	float suspensionCompression = 4.4f;
	float rollInfluence = 0.01f;  //1.0f;

	bool isFrontWheel = true;
	float connectionHeight = -0.9f;

	btVector3 connectionPointCS0(vehicleExtents.x - 2.5f, connectionHeight, vehicleExtents.z - 2.8f);
	mVehicle->addWheel(connectionPointCS0, wheelDirectionCS0, wheelAxleCS, 0.6, wheelRadius, mTuning, isFrontWheel);

	connectionPointCS0 = btVector3(-vehicleExtents.x + 2.5f, connectionHeight, vehicleExtents.z - 2.8f);
	mVehicle->addWheel(connectionPointCS0, wheelDirectionCS0, wheelAxleCS, 0.6, wheelRadius, mTuning, isFrontWheel);

	isFrontWheel = false;

	connectionPointCS0 = btVector3(vehicleExtents.x - 2.3f, connectionHeight, -vehicleExtents.z + 2.6f);
	mVehicle->addWheel(connectionPointCS0, wheelDirectionCS0, wheelAxleCS, 0.6, wheelRadius, mTuning, isFrontWheel);

	connectionPointCS0 = btVector3(-vehicleExtents.x + 2.3f, connectionHeight, -vehicleExtents.z + 2.6f);
	mVehicle->addWheel(connectionPointCS0, wheelDirectionCS0, wheelAxleCS, 0.6, wheelRadius, mTuning, isFrontWheel);

	for (int i = 0; i < mVehicle->getNumWheels(); i++)
	{
		btWheelInfo& wheel = mVehicle->getWheelInfo(i);
		wheel.m_suspensionStiffness = suspensionStiffness;
		wheel.m_wheelsDampingRelaxation = suspensionDamping;
		wheel.m_wheelsDampingCompression = suspensionCompression;
		wheel.m_frictionSlip = wheelFriction;
		wheel.m_rollInfluence = rollInfluence;
	}
}

btRigidBody* BulletWrapper::CreateRigidBody(btScalar mass, const btTransform& startTransform, btCollisionShape* shape)
{
	btAssert((!shape || shape->getShapeType() != INVALID_SHAPE_PROXYTYPE));

	bool isDynamic = (mass != 0.f);

	btVector3 localInertia(0, 0, 0);

	if (isDynamic)
		shape->calculateLocalInertia(mass, localInertia);

	btDefaultMotionState* myMotionState = new btDefaultMotionState(startTransform);

	btRigidBody::btRigidBodyConstructionInfo cInfo(mass, myMotionState, shape, localInertia);

	btRigidBody* body = new btRigidBody(cInfo);

	mBtDynamicsWorld->addRigidBody(body);
	AddShape(shape);

	return body;
}
and this video shows What happens when I use this RigidBody.

https://youtu.be/l5oHXfg1a3w

how can I solve this problem? need help.
User avatar
drleviathan
Posts: 849
Joined: Tue Sep 30, 2014 6:03 pm
Location: San Francisco

Re: Rigidbody from btBvhTriangleMeshShape doesn't collide with Others

Post by drleviathan »

I believe the btCompoundShape is designed to work with convex sub-shapes. Somewhere in the collision algorithm logic a shape->isConvex() check returns false and the result is a non-colliding body.

Edit:
In fact, btBvhTriangleMeshShape is not supported for dynamic or kinematic objects, only static. That said: I believe btBvhTriangleMeshShape sometimes works for kinematic objects if they move slowly. If you want a concave dynamic object you need to use a btCompoundShape with proper convex decomposition. Alternatively: I hear concave GImpactShapes can be dynamic (but I have never used them myself).
Post Reply