Merge remote-tracking branch 'bp/master'

This commit is contained in:
Erwin Coumans
2019-08-14 21:14:56 -07:00
54 changed files with 5626 additions and 871 deletions

View File

@@ -1,4 +1,4 @@
SUBDIRS( HelloWorld BasicDemo )
SUBDIRS( HelloWorld BasicDemo)
IF(BUILD_BULLET3)
SUBDIRS( ExampleBrowser RobotSimulator SharedMemory ThirdPartyLibs/Gwen ThirdPartyLibs/BussIK ThirdPartyLibs/clsocket OpenGLWindow TwoJoint )
ENDIF()

View File

@@ -0,0 +1,409 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2019 Google Inc. http://bulletphysics.org
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
///create 125 (5x5x5) dynamic object
#define ARRAY_SIZE_X 5
#define ARRAY_SIZE_Y 5
#define ARRAY_SIZE_Z 5
//maximum number of objects (and allow user to shoot additional boxes)
#define MAX_PROXIES (ARRAY_SIZE_X * ARRAY_SIZE_Y * ARRAY_SIZE_Z + 1024)
///scaling of the objects (0.1 = 20 centimeter boxes )
#define SCALING 1.
#define START_POS_X -5
#define START_POS_Y -5
#define START_POS_Z -3
#include "DeformableMultibody.h"
///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files.
#include "btBulletDynamicsCommon.h"
#include "BulletSoftBody/btDeformableRigidDynamicsWorld.h"
#include "BulletSoftBody/btSoftBody.h"
#include "BulletSoftBody/btSoftBodyHelpers.h"
#include "BulletSoftBody/btDeformableBodySolver.h"
#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h"
#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h"
#include <stdio.h> //printf debugging
#include "../CommonInterfaces/CommonRigidBodyBase.h"
#include "../Utils/b3ResourcePath.h"
#include "../SoftDemo/BunnyMesh.h"
#include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h"
#include "BulletDynamics/Featherstone/btMultiBodyJointFeedback.h"
#include "../CommonInterfaces/CommonMultiBodyBase.h"
#include "../Utils/b3ResourcePath.h"
///The DeformableMultibody demo deformable bodies self-collision
static bool g_floatingBase = true;
static float friction = 1.;
class DeformableMultibody : public CommonMultiBodyBase
{
btMultiBody* m_multiBody;
btAlignedObjectArray<btMultiBodyJointFeedback*> m_jointFeedbacks;
public:
DeformableMultibody(struct GUIHelperInterface* helper)
: CommonMultiBodyBase(helper)
{
}
virtual ~DeformableMultibody()
{
}
void initPhysics();
void exitPhysics();
void resetCamera()
{
float dist = 30;
float pitch = -30;
float yaw = 100;
float targetPos[3] = {0, -10, 0};
m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]);
}
virtual void stepSimulation(float deltaTime);
btMultiBody* createFeatherstoneMultiBody_testMultiDof(class btMultiBodyDynamicsWorld* world, int numLinks, const btVector3& basePosition, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents, bool spherical = false, bool floating = false);
void addColliders_testMultiDof(btMultiBody* pMultiBody, btMultiBodyDynamicsWorld* pWorld, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents);
virtual const btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() const
{
return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld;
}
virtual btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld()
{
return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld;
}
virtual void renderScene()
{
CommonMultiBodyBase::renderScene();
btDeformableRigidDynamicsWorld* deformableWorld = getDeformableDynamicsWorld();
for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++)
{
btSoftBody* psb = (btSoftBody*)deformableWorld->getSoftBodyArray()[i];
{
btSoftBodyHelpers::DrawFrame(psb, deformableWorld->getDebugDrawer());
btSoftBodyHelpers::Draw(psb, deformableWorld->getDebugDrawer(), deformableWorld->getDrawFlags());
}
}
}
};
void DeformableMultibody::initPhysics()
{
m_guiHelper->setUpAxis(1);
///collision configuration contains default setup for memory, collision setup
m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration();
///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded)
m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration);
m_broadphase = new btDbvtBroadphase();
btDeformableBodySolver* deformableBodySolver = new btDeformableBodySolver();
btMultiBodyConstraintSolver* sol;
sol = new btMultiBodyConstraintSolver;
m_solver = sol;
m_dynamicsWorld = new btDeformableRigidDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver);
deformableBodySolver->setWorld(getDeformableDynamicsWorld());
btVector3 gravity = btVector3(0, -10, 0);
m_dynamicsWorld->setGravity(gravity);
getDeformableDynamicsWorld()->getWorldInfo().m_gravity = gravity;
m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld);
{
///create a ground
btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(150.), btScalar(25.), btScalar(150.)));
m_collisionShapes.push_back(groundShape);
btTransform groundTransform;
groundTransform.setIdentity();
groundTransform.setOrigin(btVector3(0, -40, 0));
groundTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0.));
//We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here:
btScalar mass(0.);
//rigidbody is dynamic if and only if mass is non zero, otherwise static
bool isDynamic = (mass != 0.f);
btVector3 localInertia(0, 0, 0);
if (isDynamic)
groundShape->calculateLocalInertia(mass, localInertia);
//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform);
btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia);
btRigidBody* body = new btRigidBody(rbInfo);
body->setFriction(0.5);
//add the ground to the dynamics world
m_dynamicsWorld->addRigidBody(body,1,1+2);
}
{
bool damping = true;
bool gyro = false;
int numLinks = 4;
bool spherical = false; //set it ot false -to use 1DoF hinges instead of 3DoF sphericals
bool canSleep = false;
bool selfCollide = true;
btVector3 linkHalfExtents(.4, 1, .4);
btVector3 baseHalfExtents(.4, 1, .4);
btMultiBody* mbC = createFeatherstoneMultiBody_testMultiDof(m_dynamicsWorld, numLinks, btVector3(0.f, 10.f,0.f), linkHalfExtents, baseHalfExtents, spherical, g_floatingBase);
mbC->setCanSleep(canSleep);
mbC->setHasSelfCollision(selfCollide);
mbC->setUseGyroTerm(gyro);
//
if (!damping)
{
mbC->setLinearDamping(0.0f);
mbC->setAngularDamping(0.0f);
}
else
{
mbC->setLinearDamping(0.04f);
mbC->setAngularDamping(0.04f);
}
if (numLinks > 0)
{
btScalar q0 = 0.f * SIMD_PI / 180.f;
if (!spherical)
{
mbC->setJointPosMultiDof(0, &q0);
}
else
{
btQuaternion quat0(btVector3(1, 1, 0).normalized(), q0);
quat0.normalize();
mbC->setJointPosMultiDof(0, quat0);
}
}
///
addColliders_testMultiDof(mbC, m_dynamicsWorld, baseHalfExtents, linkHalfExtents);
}
// create a patch of cloth
{
btScalar h = 0;
const btScalar s = 4;
btSoftBody* psb = btSoftBodyHelpers::CreatePatch(getDeformableDynamicsWorld()->getWorldInfo(), btVector3(-s, h, -s),
btVector3(+s, h, -s),
btVector3(-s, h, +s),
btVector3(+s, h, +s),
20,20,
// 3,3,
1 + 2 + 4 + 8, true);
psb->getCollisionShape()->setMargin(0.25);
psb->generateBendingConstraints(2);
psb->setTotalMass(5);
psb->setSpringStiffness(2);
psb->setDampingCoefficient(0.01);
psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects
psb->m_cfg.kCHR = 1; // collision hardness with rigid body
psb->m_cfg.kDF = .1;
psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD;
getDeformableDynamicsWorld()->addSoftBody(psb);
getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce());
getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity));
}
m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
}
void DeformableMultibody::exitPhysics()
{
//cleanup in the reverse order of creation/initialization
//remove the rigidbodies from the dynamics world and delete them
int i;
for (i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--)
{
btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i];
btRigidBody* body = btRigidBody::upcast(obj);
if (body && body->getMotionState())
{
delete body->getMotionState();
}
m_dynamicsWorld->removeCollisionObject(obj);
delete obj;
}
//delete collision shapes
for (int j = 0; j < m_collisionShapes.size(); j++)
{
btCollisionShape* shape = m_collisionShapes[j];
delete shape;
}
m_collisionShapes.clear();
delete m_dynamicsWorld;
delete m_solver;
delete m_broadphase;
delete m_dispatcher;
delete m_collisionConfiguration;
}
void DeformableMultibody::stepSimulation(float deltaTime)
{
// getDeformableDynamicsWorld()->getMultiBodyDynamicsWorld()->stepSimulation(deltaTime);
m_dynamicsWorld->stepSimulation(deltaTime, 5, 1./250.);
}
btMultiBody* DeformableMultibody::createFeatherstoneMultiBody_testMultiDof(btMultiBodyDynamicsWorld* pWorld, int numLinks, const btVector3& basePosition, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents, bool spherical, bool floating)
{
//init the base
btVector3 baseInertiaDiag(0.f, 0.f, 0.f);
float baseMass = .1f;
if (baseMass)
{
btCollisionShape* pTempBox = new btBoxShape(btVector3(baseHalfExtents[0], baseHalfExtents[1], baseHalfExtents[2]));
pTempBox->calculateLocalInertia(baseMass, baseInertiaDiag);
delete pTempBox;
}
bool canSleep = false;
btMultiBody* pMultiBody = new btMultiBody(numLinks, baseMass, baseInertiaDiag, !floating, canSleep);
btQuaternion baseOriQuat(0.f, 0.f, 0.f, 1.f);
pMultiBody->setBasePos(basePosition);
pMultiBody->setWorldToBaseRot(baseOriQuat);
btVector3 vel(0, 0, 0);
// pMultiBody->setBaseVel(vel);
//init the links
btVector3 hingeJointAxis(1, 0, 0);
float linkMass = .1f;
btVector3 linkInertiaDiag(0.f, 0.f, 0.f);
btCollisionShape* pTempBox = new btBoxShape(btVector3(linkHalfExtents[0], linkHalfExtents[1], linkHalfExtents[2]));
pTempBox->calculateLocalInertia(linkMass, linkInertiaDiag);
delete pTempBox;
//y-axis assumed up
btVector3 parentComToCurrentCom(0, -linkHalfExtents[1] * 2.f, 0); //par body's COM to cur body's COM offset
btVector3 currentPivotToCurrentCom(0, -linkHalfExtents[1], 0); //cur body's COM to cur body's PIV offset
btVector3 parentComToCurrentPivot = parentComToCurrentCom - currentPivotToCurrentCom; //par body's COM to cur body's PIV offset
//////
btScalar q0 = 0.f * SIMD_PI / 180.f;
btQuaternion quat0(btVector3(0, 1, 0).normalized(), q0);
quat0.normalize();
/////
for (int i = 0; i < numLinks; ++i)
{
if (!spherical)
pMultiBody->setupRevolute(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f), hingeJointAxis, parentComToCurrentPivot, currentPivotToCurrentCom, true);
else
//pMultiBody->setupPlanar(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f)/*quat0*/, btVector3(1, 0, 0), parentComToCurrentPivot*2, false);
pMultiBody->setupSpherical(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f), parentComToCurrentPivot, currentPivotToCurrentCom, true);
}
pMultiBody->finalizeMultiDof();
///
pWorld->addMultiBody(pMultiBody);
///
return pMultiBody;
}
void DeformableMultibody::addColliders_testMultiDof(btMultiBody* pMultiBody, btMultiBodyDynamicsWorld* pWorld, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents)
{
btAlignedObjectArray<btQuaternion> world_to_local;
world_to_local.resize(pMultiBody->getNumLinks() + 1);
btAlignedObjectArray<btVector3> local_origin;
local_origin.resize(pMultiBody->getNumLinks() + 1);
world_to_local[0] = pMultiBody->getWorldToBaseRot();
local_origin[0] = pMultiBody->getBasePos();
{
// float pos[4]={local_origin[0].x(),local_origin[0].y(),local_origin[0].z(),1};
btScalar quat[4] = {-world_to_local[0].x(), -world_to_local[0].y(), -world_to_local[0].z(), world_to_local[0].w()};
if (1)
{
btCollisionShape* box = new btBoxShape(baseHalfExtents);
btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(pMultiBody, -1);
col->setCollisionShape(box);
btTransform tr;
tr.setIdentity();
tr.setOrigin(local_origin[0]);
tr.setRotation(btQuaternion(quat[0], quat[1], quat[2], quat[3]));
col->setWorldTransform(tr);
pWorld->addCollisionObject(col, 2, 1 + 2);
col->setFriction(friction);
pMultiBody->setBaseCollider(col);
}
}
for (int i = 0; i < pMultiBody->getNumLinks(); ++i)
{
const int parent = pMultiBody->getParent(i);
world_to_local[i + 1] = pMultiBody->getParentToLocalRot(i) * world_to_local[parent + 1];
local_origin[i + 1] = local_origin[parent + 1] + (quatRotate(world_to_local[i + 1].inverse(), pMultiBody->getRVector(i)));
}
for (int i = 0; i < pMultiBody->getNumLinks(); ++i)
{
btVector3 posr = local_origin[i + 1];
// float pos[4]={posr.x(),posr.y(),posr.z(),1};
btScalar quat[4] = {-world_to_local[i + 1].x(), -world_to_local[i + 1].y(), -world_to_local[i + 1].z(), world_to_local[i + 1].w()};
btCollisionShape* box = new btBoxShape(linkHalfExtents);
btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(pMultiBody, i);
col->setCollisionShape(box);
btTransform tr;
tr.setIdentity();
tr.setOrigin(posr);
tr.setRotation(btQuaternion(quat[0], quat[1], quat[2], quat[3]));
col->setWorldTransform(tr);
col->setFriction(friction);
pWorld->addCollisionObject(col, 2, 1 + 2);
pMultiBody->getLink(i).m_collider = col;
}
}
class CommonExampleInterface* DeformableMultibodyCreateFunc(struct CommonExampleOptions& options)
{
return new DeformableMultibody(options.m_guiHelper);
}

View File

@@ -0,0 +1,19 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2019 Google Inc. http://bulletphysics.org
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef _DEFORMABLE_MULTIBODY_H
#define _DEFORMABLE_MULTIBODY_H
class CommonExampleInterface* DeformableMultibodyCreateFunc(struct CommonExampleOptions& options);
#endif //_DEFORMABLE_MULTIBODY_H

View File

@@ -0,0 +1,291 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2019 Google Inc. http://bulletphysics.org
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
///create 125 (5x5x5) dynamic object
#define ARRAY_SIZE_X 5
#define ARRAY_SIZE_Y 5
#define ARRAY_SIZE_Z 5
//maximum number of objects (and allow user to shoot additional boxes)
#define MAX_PROXIES (ARRAY_SIZE_X * ARRAY_SIZE_Y * ARRAY_SIZE_Z + 1024)
///scaling of the objects (0.1 = 20 centimeter boxes )
#define SCALING 1.
#define START_POS_X -5
#define START_POS_Y -5
#define START_POS_Z -3
#include "DeformableRigid.h"
///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files.
#include "btBulletDynamicsCommon.h"
#include "BulletSoftBody/btDeformableRigidDynamicsWorld.h"
#include "BulletSoftBody/btSoftBody.h"
#include "BulletSoftBody/btSoftBodyHelpers.h"
#include "BulletSoftBody/btDeformableBodySolver.h"
#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h"
#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h"
#include <stdio.h> //printf debugging
#include "../CommonInterfaces/CommonRigidBodyBase.h"
#include "../Utils/b3ResourcePath.h"
///The DeformableRigid shows the use of rolling friction.
///Spheres will come to a rest on a sloped plane using a constraint. Damping cannot achieve the same.
///Generally it is best to leave the rolling friction coefficient zero (or close to zero).
class DeformableRigid : public CommonRigidBodyBase
{
public:
DeformableRigid(struct GUIHelperInterface* helper)
: CommonRigidBodyBase(helper)
{
}
virtual ~DeformableRigid()
{
}
void initPhysics();
void exitPhysics();
void resetCamera()
{
float dist = 20;
float pitch = -45;
float yaw = 100;
float targetPos[3] = {0, -3, 0};
m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]);
}
void stepSimulation(float deltaTime)
{
//use a smaller internal timestep, there are stability issues
float internalTimeStep = 1. / 240.f;
m_dynamicsWorld->stepSimulation(deltaTime, 4, internalTimeStep);
}
void Ctor_RbUpStack(int count)
{
float mass = 0.2;
btCompoundShape* cylinderCompound = new btCompoundShape;
btCollisionShape* cylinderShape = new btCylinderShapeX(btVector3(2, .5, .5));
btCollisionShape* boxShape = new btBoxShape(btVector3(2, .5, .5));
btTransform localTransform;
localTransform.setIdentity();
cylinderCompound->addChildShape(localTransform, boxShape);
btQuaternion orn(SIMD_HALF_PI, 0, 0);
localTransform.setRotation(orn);
// localTransform.setOrigin(btVector3(1,1,1));
cylinderCompound->addChildShape(localTransform, cylinderShape);
btCollisionShape* shape[] = {
new btBoxShape(btVector3(1, 1, 1)),
// new btSphereShape(0.75),
// cylinderCompound
};
// static const int nshapes = sizeof(shape) / sizeof(shape[0]);
// for (int i = 0; i < count; ++i)
// {
// btTransform startTransform;
// startTransform.setIdentity();
// startTransform.setOrigin(btVector3(0, 2+ 2 * i, 0));
// startTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0.));
// createRigidBody(mass, startTransform, shape[i % nshapes]);
// }
btTransform startTransform;
startTransform.setIdentity();
startTransform.setOrigin(btVector3(1, 1.5, 1));
createRigidBody(mass, startTransform, shape[0]);
startTransform.setOrigin(btVector3(1, 1.5, -1));
createRigidBody(mass, startTransform, shape[0]);
startTransform.setOrigin(btVector3(-1, 1.5, 1));
createRigidBody(mass, startTransform, shape[0]);
startTransform.setOrigin(btVector3(-1, 1.5, -1));
createRigidBody(mass, startTransform, shape[0]);
startTransform.setOrigin(btVector3(0, 3.5, 0));
createRigidBody(mass, startTransform, shape[0]);
}
virtual const btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() const
{
///just make it a btSoftRigidDynamicsWorld please
///or we will add type checking
return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld;
}
virtual btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld()
{
///just make it a btSoftRigidDynamicsWorld please
///or we will add type checking
return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld;
}
virtual void renderScene()
{
CommonRigidBodyBase::renderScene();
btDeformableRigidDynamicsWorld* deformableWorld = getDeformableDynamicsWorld();
for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++)
{
btSoftBody* psb = (btSoftBody*)deformableWorld->getSoftBodyArray()[i];
//if (softWorld->getDebugDrawer() && !(softWorld->getDebugDrawer()->getDebugMode() & (btIDebugDraw::DBG_DrawWireframe)))
{
btSoftBodyHelpers::DrawFrame(psb, deformableWorld->getDebugDrawer());
btSoftBodyHelpers::Draw(psb, deformableWorld->getDebugDrawer(), deformableWorld->getDrawFlags());
}
}
}
};
void DeformableRigid::initPhysics()
{
m_guiHelper->setUpAxis(1);
///collision configuration contains default setup for memory, collision setup
m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration();
///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded)
m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration);
m_broadphase = new btDbvtBroadphase();
btDeformableBodySolver* deformableBodySolver = new btDeformableBodySolver();
///the default constraint solver. For parallel processing you can use a different solver (see Extras/BulletMultiThreaded)
btMultiBodyConstraintSolver* sol = new btMultiBodyConstraintSolver();
m_solver = sol;
m_dynamicsWorld = new btDeformableRigidDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver);
deformableBodySolver->setWorld(getDeformableDynamicsWorld());
// m_dynamicsWorld->getSolverInfo().m_singleAxisDeformableThreshold = 0.f;//faster but lower quality
btVector3 gravity = btVector3(0, -10, 0);
m_dynamicsWorld->setGravity(gravity);
getDeformableDynamicsWorld()->getWorldInfo().m_gravity = gravity;
// getDeformableDynamicsWorld()->before_solver_callbacks.push_back(dynamics);
m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld);
{
///create a ground
btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(150.), btScalar(25.), btScalar(150.)));
m_collisionShapes.push_back(groundShape);
btTransform groundTransform;
groundTransform.setIdentity();
groundTransform.setOrigin(btVector3(0, -32, 0));
groundTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0.));
//We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here:
btScalar mass(0.);
//rigidbody is dynamic if and only if mass is non zero, otherwise static
bool isDynamic = (mass != 0.f);
btVector3 localInertia(0, 0, 0);
if (isDynamic)
groundShape->calculateLocalInertia(mass, localInertia);
//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform);
btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia);
btRigidBody* body = new btRigidBody(rbInfo);
body->setFriction(1);
//add the ground to the dynamics world
m_dynamicsWorld->addRigidBody(body);
}
// create a piece of cloth
{
bool onGround = false;
const btScalar s = 4;
btSoftBody* psb = btSoftBodyHelpers::CreatePatch(getDeformableDynamicsWorld()->getWorldInfo(), btVector3(-s, 0, -s),
btVector3(+s, 0, -s),
btVector3(-s, 0, +s),
btVector3(+s, 0, +s),
// 3,3,
20,20,
1 + 2 + 4 + 8, true);
// 0, true);
if (onGround)
psb = btSoftBodyHelpers::CreatePatch(getDeformableDynamicsWorld()->getWorldInfo(), btVector3(-s, 0, -s),
btVector3(+s, 0, -s),
btVector3(-s, 0, +s),
btVector3(+s, 0, +s),
// 20,20,
2,2,
0, true);
psb->getCollisionShape()->setMargin(0.1);
psb->generateBendingConstraints(2);
psb->setTotalMass(1);
psb->setSpringStiffness(1);
psb->setDampingCoefficient(0.01);
psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects
psb->m_cfg.kCHR = 1; // collision hardness with rigid body
psb->m_cfg.kDF = 1;
psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD;
getDeformableDynamicsWorld()->addSoftBody(psb);
getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce());
getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity));
// add a few rigid bodies
Ctor_RbUpStack(1);
}
m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
}
void DeformableRigid::exitPhysics()
{
//cleanup in the reverse order of creation/initialization
//remove the rigidbodies from the dynamics world and delete them
int i;
for (i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--)
{
btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i];
btRigidBody* body = btRigidBody::upcast(obj);
if (body && body->getMotionState())
{
delete body->getMotionState();
}
m_dynamicsWorld->removeCollisionObject(obj);
delete obj;
}
//delete collision shapes
for (int j = 0; j < m_collisionShapes.size(); j++)
{
btCollisionShape* shape = m_collisionShapes[j];
delete shape;
}
m_collisionShapes.clear();
delete m_dynamicsWorld;
delete m_solver;
delete m_broadphase;
delete m_dispatcher;
delete m_collisionConfiguration;
}
class CommonExampleInterface* DeformableRigidCreateFunc(struct CommonExampleOptions& options)
{
return new DeformableRigid(options.m_guiHelper);
}

View File

@@ -0,0 +1,19 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2019 Google Inc. http://bulletphysics.org
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef _DEFORMABLE_RIGID_H
#define _DEFORMABLE_RIGID_H
class CommonExampleInterface* DeformableRigidCreateFunc(struct CommonExampleOptions& options);
#endif //_DEFORMABLE_RIGID_H

View File

@@ -0,0 +1,397 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2019 Google Inc. http://bulletphysics.org
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
///create 125 (5x5x5) dynamic object
#define ARRAY_SIZE_X 5
#define ARRAY_SIZE_Y 5
#define ARRAY_SIZE_Z 5
//maximum number of objects (and allow user to shoot additional boxes)
#define MAX_PROXIES (ARRAY_SIZE_X * ARRAY_SIZE_Y * ARRAY_SIZE_Z + 1024)
///scaling of the objects (0.1 = 20 centimeter boxes )
#define SCALING 1.
#define START_POS_X -5
#define START_POS_Y -5
#define START_POS_Z -3
#include "Pinch.h"
///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files.
#include "btBulletDynamicsCommon.h"
#include "BulletSoftBody/btDeformableRigidDynamicsWorld.h"
#include "BulletSoftBody/btSoftBody.h"
#include "BulletSoftBody/btSoftBodyHelpers.h"
#include "BulletSoftBody/btDeformableBodySolver.h"
#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h"
#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h"
#include <stdio.h> //printf debugging
#include "../CommonInterfaces/CommonRigidBodyBase.h"
#include "../Utils/b3ResourcePath.h"
///The Pinch shows the use of rolling friction.
///Spheres will come to a rest on a sloped plane using a constraint. Damping cannot achieve the same.
///Generally it is best to leave the rolling friction coefficient zero (or close to zero).
struct TetraCube
{
#include "../SoftDemo/cube.inl"
};
struct TetraBunny
{
#include "../SoftDemo/bunny.inl"
};
class Pinch : public CommonRigidBodyBase
{
public:
Pinch(struct GUIHelperInterface* helper)
: CommonRigidBodyBase(helper)
{
}
virtual ~Pinch()
{
}
void initPhysics();
void exitPhysics();
void resetCamera()
{
float dist = 25;
float pitch = -30;
float yaw = 100;
float targetPos[3] = {0, -0, 0};
m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]);
}
void stepSimulation(float deltaTime)
{
//use a smaller internal timestep, there are stability issues
float internalTimeStep = 1. / 240.f;
m_dynamicsWorld->stepSimulation(deltaTime, 4, internalTimeStep);
}
void createGrip()
{
int count = 2;
float mass = 1e6;
btCollisionShape* shape[] = {
new btBoxShape(btVector3(3, 3, 0.5)),
};
static const int nshapes = sizeof(shape) / sizeof(shape[0]);
for (int i = 0; i < count; ++i)
{
btTransform startTransform;
startTransform.setIdentity();
startTransform.setOrigin(btVector3(10, 0, 0));
startTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0.));
createRigidBody(mass, startTransform, shape[i % nshapes]);
}
}
virtual const btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() const
{
return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld;
}
virtual btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld()
{
return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld;
}
virtual void renderScene()
{
CommonRigidBodyBase::renderScene();
btDeformableRigidDynamicsWorld* deformableWorld = getDeformableDynamicsWorld();
for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++)
{
btSoftBody* psb = (btSoftBody*)deformableWorld->getSoftBodyArray()[i];
{
btSoftBodyHelpers::DrawFrame(psb, deformableWorld->getDebugDrawer());
btSoftBodyHelpers::Draw(psb, deformableWorld->getDebugDrawer(), deformableWorld->getDrawFlags());
}
}
}
};
void dynamics(btScalar time, btDeformableRigidDynamicsWorld* world)
{
btAlignedObjectArray<btRigidBody*>& rbs = world->getNonStaticRigidBodies();
if (rbs.size()<2)
return;
btRigidBody* rb0 = rbs[0];
btScalar pressTime = 0.9;
btScalar liftTime = 2.5;
btScalar shiftTime = 3.5;
btScalar holdTime = 4.5*1000;
btScalar dropTime = 5.3*1000;
btTransform rbTransform;
rbTransform.setIdentity();
btVector3 translation;
btVector3 velocity;
btVector3 initialTranslationLeft = btVector3(0.5,3,4);
btVector3 initialTranslationRight = btVector3(0.5,3,-4);
btVector3 pinchVelocityLeft = btVector3(0,0,-2);
btVector3 pinchVelocityRight = btVector3(0,0,2);
btVector3 liftVelocity = btVector3(0,5,0);
btVector3 shiftVelocity = btVector3(0,0,5);
btVector3 holdVelocity = btVector3(0,0,0);
btVector3 openVelocityLeft = btVector3(0,0,4);
btVector3 openVelocityRight = btVector3(0,0,-4);
if (time < pressTime)
{
velocity = pinchVelocityLeft;
translation = initialTranslationLeft + pinchVelocityLeft * time;
}
else if (time < liftTime)
{
velocity = liftVelocity;
translation = initialTranslationLeft + pinchVelocityLeft * pressTime + liftVelocity * (time - pressTime);
}
else if (time < shiftTime)
{
velocity = shiftVelocity;
translation = initialTranslationLeft + pinchVelocityLeft * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (time - liftTime);
}
else if (time < holdTime)
{
velocity = btVector3(0,0,0);
translation = initialTranslationLeft + pinchVelocityLeft * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (shiftTime - liftTime) + holdVelocity * (time - shiftTime);
}
else if (time < dropTime)
{
velocity = openVelocityLeft;
translation = initialTranslationLeft + pinchVelocityLeft * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (shiftTime - liftTime) + holdVelocity * (holdTime - shiftTime)+ openVelocityLeft * (time - holdTime);
}
else
{
velocity = holdVelocity;
translation = initialTranslationLeft + pinchVelocityLeft * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (shiftTime - liftTime) + holdVelocity * (holdTime - shiftTime)+ openVelocityLeft * (dropTime - holdTime);
}
rbTransform.setOrigin(translation);
rbTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0));
rb0->setCenterOfMassTransform(rbTransform);
rb0->setAngularVelocity(btVector3(0,0,0));
rb0->setLinearVelocity(velocity);
btRigidBody* rb1 = rbs[1];
if (time < pressTime)
{
velocity = pinchVelocityRight;
translation = initialTranslationRight + pinchVelocityRight * time;
}
else if (time < liftTime)
{
velocity = liftVelocity;
translation = initialTranslationRight + pinchVelocityRight * pressTime + liftVelocity * (time - pressTime);
}
else if (time < shiftTime)
{
velocity = shiftVelocity;
translation = initialTranslationRight + pinchVelocityRight * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (time - liftTime);
}
else if (time < holdTime)
{
velocity = btVector3(0,0,0);
translation = initialTranslationRight + pinchVelocityRight * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (shiftTime - liftTime) + holdVelocity * (time - shiftTime);
}
else if (time < dropTime)
{
velocity = openVelocityRight;
translation = initialTranslationRight + pinchVelocityRight * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (shiftTime - liftTime) + holdVelocity * (holdTime - shiftTime)+ openVelocityRight * (time - holdTime);
}
else
{
velocity = holdVelocity;
translation = initialTranslationRight + pinchVelocityRight * pressTime + liftVelocity * (liftTime-pressTime) + shiftVelocity * (shiftTime - liftTime) + holdVelocity * (holdTime - shiftTime)+ openVelocityRight * (dropTime - holdTime);
}
rbTransform.setOrigin(translation);
rbTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0));
rb1->setCenterOfMassTransform(rbTransform);
rb1->setAngularVelocity(btVector3(0,0,0));
rb1->setLinearVelocity(velocity);
rb0->setFriction(20);
rb1->setFriction(20);
}
void Pinch::initPhysics()
{
m_guiHelper->setUpAxis(1);
m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration();
m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration);
m_broadphase = new btDbvtBroadphase();
btDeformableBodySolver* deformableBodySolver = new btDeformableBodySolver();
btMultiBodyConstraintSolver* sol = new btMultiBodyConstraintSolver();
m_solver = sol;
m_dynamicsWorld = new btDeformableRigidDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver);
deformableBodySolver->setWorld(getDeformableDynamicsWorld());
// m_dynamicsWorld->getSolverInfo().m_singleAxisDeformableThreshold = 0.f;//faster but lower quality
btVector3 gravity = btVector3(0, -10, 0);
m_dynamicsWorld->setGravity(gravity);
getDeformableDynamicsWorld()->getWorldInfo().m_gravity = gravity;
getDeformableDynamicsWorld()->setSolverCallback(dynamics);
m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld);
//create a ground
{
btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(150.), btScalar(25.), btScalar(150.)));
m_collisionShapes.push_back(groundShape);
btTransform groundTransform;
groundTransform.setIdentity();
groundTransform.setOrigin(btVector3(0, -25, 0));
groundTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0));
//We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here:
btScalar mass(0.);
//rigidbody is dynamic if and only if mass is non zero, otherwise static
bool isDynamic = (mass != 0.f);
btVector3 localInertia(0, 0, 0);
if (isDynamic)
groundShape->calculateLocalInertia(mass, localInertia);
//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform);
btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia);
btRigidBody* body = new btRigidBody(rbInfo);
body->setFriction(0.5);
//add the ground to the dynamics world
m_dynamicsWorld->addRigidBody(body);
}
// create a soft block
{
btScalar verts[24] = {0.f, 0.f, 0.f,
1.f, 0.f, 0.f,
0.f, 1.f, 0.f,
0.f, 0.f, 1.f,
1.f, 1.f, 0.f,
0.f, 1.f, 1.f,
1.f, 0.f, 1.f,
1.f, 1.f, 1.f
};
int triangles[60] = {0, 6, 3,
0,1,6,
7,5,3,
7,3,6,
4,7,6,
4,6,1,
7,2,5,
7,4,2,
0,3,2,
2,3,5,
0,2,4,
0,4,1,
0,6,5,
0,6,4,
3,4,2,
3,4,7,
2,7,3,
2,7,1,
4,5,0,
4,5,6,
};
// btSoftBody* psb = btSoftBodyHelpers::CreateFromTriMesh(getDeformableDynamicsWorld()->getWorldInfo(), &verts[0], &triangles[0], 20);
////
btSoftBody* psb = btSoftBodyHelpers::CreateFromTetGenData(getDeformableDynamicsWorld()->getWorldInfo(),
TetraCube::getElements(),
0,
TetraCube::getNodes(),
false, true, true);
psb->scale(btVector3(2, 2, 2));
psb->translate(btVector3(0, 4, 0));
psb->getCollisionShape()->setMargin(0.1);
psb->setTotalMass(1);
// psb->scale(btVector3(5, 5, 5));
// psb->translate(btVector3(-2.5, 4, -2.5));
// psb->getCollisionShape()->setMargin(0.1);
// psb->setTotalMass(1);
psb->setSpringStiffness(2);
psb->setDampingCoefficient(0.02);
psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects
psb->m_cfg.kCHR = 1; // collision hardness with rigid body
psb->m_cfg.kDF = 2;
psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD;
getDeformableDynamicsWorld()->addSoftBody(psb);
getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce());
getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity));
// add a grippers
createGrip();
}
m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
}
void Pinch::exitPhysics()
{
//cleanup in the reverse order of creation/initialization
//remove the rigidbodies from the dynamics world and delete them
int i;
for (i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--)
{
btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i];
btRigidBody* body = btRigidBody::upcast(obj);
if (body && body->getMotionState())
{
delete body->getMotionState();
}
m_dynamicsWorld->removeCollisionObject(obj);
delete obj;
}
//delete collision shapes
for (int j = 0; j < m_collisionShapes.size(); j++)
{
btCollisionShape* shape = m_collisionShapes[j];
delete shape;
}
m_collisionShapes.clear();
delete m_dynamicsWorld;
delete m_solver;
delete m_broadphase;
delete m_dispatcher;
delete m_collisionConfiguration;
}
class CommonExampleInterface* PinchCreateFunc(struct CommonExampleOptions& options)
{
return new Pinch(options.m_guiHelper);
}

View File

@@ -0,0 +1,19 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2019 Google Inc. http://bulletphysics.org
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef _PINCH_H
#define _PINCH_H
class CommonExampleInterface* PinchCreateFunc(struct CommonExampleOptions& options);
#endif //_PINCH_H

View File

@@ -0,0 +1,296 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2019 Google Inc. http://bulletphysics.org
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
///create 125 (5x5x5) dynamic object
#define ARRAY_SIZE_X 5
#define ARRAY_SIZE_Y 5
#define ARRAY_SIZE_Z 5
//maximum number of objects (and allow user to shoot additional boxes)
#define MAX_PROXIES (ARRAY_SIZE_X * ARRAY_SIZE_Y * ARRAY_SIZE_Z + 1024)
///scaling of the objects (0.1 = 20 centimeter boxes )
#define SCALING 1.
#define START_POS_X -5
#define START_POS_Y -5
#define START_POS_Z -3
#include "VolumetricDeformable.h"
///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files.
#include "btBulletDynamicsCommon.h"
#include "BulletSoftBody/btDeformableRigidDynamicsWorld.h"
#include "BulletSoftBody/btSoftBody.h"
#include "BulletSoftBody/btSoftBodyHelpers.h"
#include "BulletSoftBody/btDeformableBodySolver.h"
#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h"
#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h"
#include <stdio.h> //printf debugging
#include "../CommonInterfaces/CommonRigidBodyBase.h"
#include "../Utils/b3ResourcePath.h"
///The VolumetricDeformable shows the use of rolling friction.
///Spheres will come to a rest on a sloped plane using a constraint. Damping cannot achieve the same.
///Generally it is best to leave the rolling friction coefficient zero (or close to zero).
struct TetraCube
{
#include "../SoftDemo/cube.inl"
};
class VolumetricDeformable : public CommonRigidBodyBase
{
public:
VolumetricDeformable(struct GUIHelperInterface* helper)
: CommonRigidBodyBase(helper)
{
}
virtual ~VolumetricDeformable()
{
}
void initPhysics();
void exitPhysics();
void resetCamera()
{
float dist = 20;
float pitch = -45;
float yaw = 100;
float targetPos[3] = {0, 3, 0};
m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]);
}
void stepSimulation(float deltaTime)
{
//use a smaller internal timestep, there are stability issues
float internalTimeStep = 1. / 240.f;
m_dynamicsWorld->stepSimulation(deltaTime, 4, internalTimeStep);
}
void createStaticBox(const btVector3& halfEdge, const btVector3& translation)
{
btCollisionShape* box = new btBoxShape(halfEdge);
m_collisionShapes.push_back(box);
btTransform Transform;
Transform.setIdentity();
Transform.setOrigin(translation);
Transform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0.0));
//We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here:
btScalar mass(0.);
//rigidbody is dynamic if and only if mass is non zero, otherwise static
bool isDynamic = (mass != 0.f);
btVector3 localInertia(0, 0, 0);
if (isDynamic)
box->calculateLocalInertia(mass, localInertia);
//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
btDefaultMotionState* myMotionState = new btDefaultMotionState(Transform);
btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, box, localInertia);
btRigidBody* body = new btRigidBody(rbInfo);
body->setFriction(0.5);
//add the ground to the dynamics world
m_dynamicsWorld->addRigidBody(body);
}
void Ctor_RbUpStack(int count)
{
float mass = 0.02;
btCompoundShape* cylinderCompound = new btCompoundShape;
btCollisionShape* cylinderShape = new btCylinderShapeX(btVector3(2, .5, .5));
btCollisionShape* boxShape = new btBoxShape(btVector3(2, .5, .5));
btTransform localTransform;
localTransform.setIdentity();
cylinderCompound->addChildShape(localTransform, boxShape);
btQuaternion orn(SIMD_HALF_PI, 0, 0);
localTransform.setRotation(orn);
// localTransform.setOrigin(btVector3(1,1,1));
cylinderCompound->addChildShape(localTransform, cylinderShape);
btCollisionShape* shape[] = {
new btBoxShape(btVector3(1, 1, 1)),
};
static const int nshapes = sizeof(shape) / sizeof(shape[0]);
for (int i = 0; i < count; ++i)
{
btTransform startTransform;
startTransform.setIdentity();
startTransform.setOrigin(btVector3(i, 10 + 2 * i, i-1));
createRigidBody(mass, startTransform, shape[i % nshapes]);
}
}
virtual const btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld() const
{
///just make it a btSoftRigidDynamicsWorld please
///or we will add type checking
return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld;
}
virtual btDeformableRigidDynamicsWorld* getDeformableDynamicsWorld()
{
///just make it a btSoftRigidDynamicsWorld please
///or we will add type checking
return (btDeformableRigidDynamicsWorld*)m_dynamicsWorld;
}
virtual void renderScene()
{
CommonRigidBodyBase::renderScene();
btDeformableRigidDynamicsWorld* deformableWorld = getDeformableDynamicsWorld();
for (int i = 0; i < deformableWorld->getSoftBodyArray().size(); i++)
{
btSoftBody* psb = (btSoftBody*)deformableWorld->getSoftBodyArray()[i];
//if (softWorld->getDebugDrawer() && !(softWorld->getDebugDrawer()->getDebugMode() & (btIDebugDraw::DBG_DrawWireframe)))
{
btSoftBodyHelpers::DrawFrame(psb, deformableWorld->getDebugDrawer());
btSoftBodyHelpers::Draw(psb, deformableWorld->getDebugDrawer(), deformableWorld->getDrawFlags());
}
}
}
};
void VolumetricDeformable::initPhysics()
{
m_guiHelper->setUpAxis(1);
///collision configuration contains default setup for memory, collision setup
m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration();
///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded)
m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration);
m_broadphase = new btDbvtBroadphase();
btDeformableBodySolver* deformableBodySolver = new btDeformableBodySolver();
///the default constraint solver. For parallel processing you can use a different solver (see Extras/BulletMultiThreaded)
btMultiBodyConstraintSolver* sol = new btMultiBodyConstraintSolver();
m_solver = sol;
m_dynamicsWorld = new btDeformableRigidDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver);
deformableBodySolver->setWorld(getDeformableDynamicsWorld());
// m_dynamicsWorld->getSolverInfo().m_singleAxisDeformableThreshold = 0.f;//faster but lower quality
btVector3 gravity = btVector3(0, -10, 0);
m_dynamicsWorld->setGravity(gravity);
getDeformableDynamicsWorld()->getWorldInfo().m_gravity = gravity;
m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld);
{
///create a ground
btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(150.), btScalar(50.), btScalar(150.)));
m_collisionShapes.push_back(groundShape);
btTransform groundTransform;
groundTransform.setIdentity();
groundTransform.setOrigin(btVector3(0, -50, 0));
groundTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0.0));
//We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here:
btScalar mass(0.);
//rigidbody is dynamic if and only if mass is non zero, otherwise static
bool isDynamic = (mass != 0.f);
btVector3 localInertia(0, 0, 0);
if (isDynamic)
groundShape->calculateLocalInertia(mass, localInertia);
//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform);
btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia);
btRigidBody* body = new btRigidBody(rbInfo);
body->setFriction(0.5);
//add the ground to the dynamics world
m_dynamicsWorld->addRigidBody(body);
}
createStaticBox(btVector3(1, 5, 5), btVector3(-5,0,0));
createStaticBox(btVector3(1, 5, 5), btVector3(5,0,0));
createStaticBox(btVector3(5, 5, 1), btVector3(0,0,5));
createStaticBox(btVector3(5, 5, 1), btVector3(0,0,-5));
// create volumetric soft body
{
btSoftBody* psb = btSoftBodyHelpers::CreateFromTetGenData(getDeformableDynamicsWorld()->getWorldInfo(),
TetraCube::getElements(),
0,
TetraCube::getNodes(),
false, true, true);
getDeformableDynamicsWorld()->addSoftBody(psb);
psb->scale(btVector3(2, 2, 2));
psb->translate(btVector3(0, 5, 0));
// psb->setVolumeMass(10);
psb->getCollisionShape()->setMargin(0.25);
// psb->generateBendingConstraints(2);
psb->setTotalMass(1);
psb->setSpringStiffness(1);
psb->setDampingCoefficient(0.01);
psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects
psb->m_cfg.kCHR = 1; // collision hardness with rigid body
psb->m_cfg.kDF = 0.5;
psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD;
getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce());
getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity));
}
// add a few rigid bodies
Ctor_RbUpStack(4);
m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
}
void VolumetricDeformable::exitPhysics()
{
//cleanup in the reverse order of creation/initialization
//remove the rigidbodies from the dynamics world and delete them
int i;
for (i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--)
{
btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i];
btRigidBody* body = btRigidBody::upcast(obj);
if (body && body->getMotionState())
{
delete body->getMotionState();
}
m_dynamicsWorld->removeCollisionObject(obj);
delete obj;
}
//delete collision shapes
for (int j = 0; j < m_collisionShapes.size(); j++)
{
btCollisionShape* shape = m_collisionShapes[j];
delete shape;
}
m_collisionShapes.clear();
delete m_dynamicsWorld;
delete m_solver;
delete m_broadphase;
delete m_dispatcher;
delete m_collisionConfiguration;
}
class CommonExampleInterface* VolumetricDeformableCreateFunc(struct CommonExampleOptions& options)
{
return new VolumetricDeformable(options.m_guiHelper);
}

View File

@@ -0,0 +1,19 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2019 Google Inc. http://bulletphysics.org
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef _VOLUMETRIC_DEFORMABLE_H
#define _VOLUMETRIC_DEFORMABLE_H
class CommonExampleInterface* VolumetricDeformableCreateFunc(struct CommonExampleOptions& options);
#endif //_VOLUMETRIC_DEFORMABLE__H

View File

@@ -359,6 +359,14 @@ SET(BulletExampleBrowser_SRCS
../MultiBody/MultiBodyConstraintFeedback.cpp
../SoftDemo/SoftDemo.cpp
../SoftDemo/SoftDemo.h
../DeformableDemo/Pinch.cpp
../DeformableDemo/Pinch.h
../DeformableDemo/DeformableMultibody.cpp
../DeformableDemo/DeformableMultibody.h
../DeformableDemo/DeformableRigid.cpp
../DeformableDemo/DeformableRigid.h
../DeformableDemo/VolumetricDeformable.cpp
../DeformableDemo/VolumetricDeformable.h
../MultiBody/MultiDofDemo.cpp
../MultiBody/MultiDofDemo.h
../RigidBody/RigidBodySoftContact.cpp

View File

@@ -47,6 +47,10 @@
#include "../FractureDemo/FractureDemo.h"
#include "../DynamicControlDemo/MotorDemo.h"
#include "../RollingFrictionDemo/RollingFrictionDemo.h"
#include "../DeformableDemo/DeformableRigid.h"
#include "../DeformableDemo/Pinch.h"
#include "../DeformableDemo/DeformableMultibody.h"
#include "../DeformableDemo/VolumetricDeformable.h"
#include "../SharedMemory/PhysicsServerExampleBullet2.h"
#include "../SharedMemory/PhysicsServerExample.h"
#include "../SharedMemory/PhysicsClientExample.h"
@@ -117,7 +121,7 @@ static ExampleEntry gDefaultExamples[] =
ExampleEntry(1, "Basic Example", "Create some rigid bodies using box collision shapes. This is a good example to familiarize with the basic initialization of Bullet. The Basic Example can also be compiled without graphical user interface, as a console application. Press W for wireframe, A to show AABBs, I to suspend/restart physics simulation. Press D to toggle auto-deactivation of the simulation. ", BasicExampleCreateFunc),
ExampleEntry(1, "Rolling Friction", "Damping is often not good enough to keep rounded objects from rolling down a sloped surface. Instead, you can set the rolling friction of a rigid body. Generally it is best to leave the rolling friction to zero, to avoid artifacts.", RollingFrictionCreateFunc),
ExampleEntry(1, "Constraints", "Show the use of the various constraints in Bullet. Press the L key to visualize the constraint limits. Press the C key to visualize the constraint frames.",
AllConstraintCreateFunc),
@@ -190,6 +194,13 @@ static ExampleEntry gDefaultExamples[] =
ExampleEntry(1, "Spheres & Plane C-API (Bullet2)", "Collision C-API using Bullet 2.x backend", CollisionTutorialBullet2CreateFunc, TUT_SPHERE_PLANE_BULLET2),
//ExampleEntry(1, "Spheres & Plane C-API (Bullet3)", "Collision C-API using Bullet 3.x backend", CollisionTutorialBullet2CreateFunc,TUT_SPHERE_PLANE_RTB3),
ExampleEntry(0, "Deformabe Body"),
ExampleEntry(1, "Deformable-RigidBody Contact", "Deformable test", DeformableRigidCreateFunc),
ExampleEntry(1, "Grasp Deformable Cube", "Grasping test", PinchCreateFunc),
ExampleEntry(1, "Volumetric Deformable Objects", "Volumetric Deformable test", VolumetricDeformableCreateFunc),
ExampleEntry(1, "Deformable-MultiBody Contact", "MultiBody and Deformable contact", DeformableMultibodyCreateFunc),
// ExampleEntry(1, "MultiBody Baseline", "MultiBody Baseline", MultiBodyBaselineCreateFunc),
#ifdef INCLUDE_CLOTH_DEMOS
ExampleEntry(0, "Soft Body"),
ExampleEntry(1, "Cloth", "Simulate a patch of cloth.", SoftDemoCreateFunc, 0),

View File

@@ -182,6 +182,7 @@ project "App_BulletExampleBrowser"
"../RenderingExamples/*",
"../VoronoiFracture/*",
"../SoftDemo/*",
"../DeformableDemo/*",
"../RollingFrictionDemo/*",
"../rbdl/*",
"../FractureDemo/*",

View File

@@ -2265,7 +2265,7 @@ int BulletMJCFImporter::getBodyUniqueId() const
return m_data->m_activeBodyUniqueId;
}
static btCollisionShape* MjcfCreateConvexHullFromShapes(std::vector<tinyobj::shape_t>& shapes, const btVector3& geomScale, btScalar collisionMargin)
static btCollisionShape* MjcfCreateConvexHullFromShapes(const tinyobj::attrib_t& attribute, std::vector<tinyobj::shape_t>& shapes, const btVector3& geomScale, btScalar collisionMargin)
{
btCompoundShape* compound = new btCompoundShape();
compound->setMargin(collisionMargin);
@@ -2278,25 +2278,26 @@ static btCollisionShape* MjcfCreateConvexHullFromShapes(std::vector<tinyobj::sha
btConvexHullShape* convexHull = new btConvexHullShape();
convexHull->setMargin(collisionMargin);
tinyobj::shape_t& shape = shapes[s];
int faceCount = shape.mesh.indices.size();
for (int f = 0; f < faceCount; f += 3)
{
btVector3 pt;
pt.setValue(shape.mesh.positions[shape.mesh.indices[f] * 3 + 0],
shape.mesh.positions[shape.mesh.indices[f] * 3 + 1],
shape.mesh.positions[shape.mesh.indices[f] * 3 + 2]);
pt.setValue(attribute.vertices[3 * shape.mesh.indices[f].vertex_index + 0],
attribute.vertices[3 * shape.mesh.indices[f].vertex_index + 1],
attribute.vertices[3 * shape.mesh.indices[f].vertex_index + 2]);
convexHull->addPoint(pt * geomScale, false);
pt.setValue(shape.mesh.positions[shape.mesh.indices[f + 1] * 3 + 0],
shape.mesh.positions[shape.mesh.indices[f + 1] * 3 + 1],
shape.mesh.positions[shape.mesh.indices[f + 1] * 3 + 2]);
pt.setValue(attribute.vertices[3 * shape.mesh.indices[f + 1].vertex_index + 0],
attribute.vertices[3 * shape.mesh.indices[f + 1].vertex_index + 1],
attribute.vertices[3 * shape.mesh.indices[f + 1].vertex_index + 2]);
convexHull->addPoint(pt * geomScale, false);
pt.setValue(shape.mesh.positions[shape.mesh.indices[f + 2] * 3 + 0],
shape.mesh.positions[shape.mesh.indices[f + 2] * 3 + 1],
shape.mesh.positions[shape.mesh.indices[f + 2] * 3 + 2]);
pt.setValue(attribute.vertices[3 * shape.mesh.indices[f + 2].vertex_index + 0],
attribute.vertices[3 * shape.mesh.indices[f + 2].vertex_index + 1],
attribute.vertices[3 * shape.mesh.indices[f + 2].vertex_index + 2]);
convexHull->addPoint(pt * geomScale, false);
}
@@ -2391,10 +2392,11 @@ class btCompoundShape* BulletMJCFImporter::convertLinkCollisionShapes(int linkIn
else
{
std::vector<tinyobj::shape_t> shapes;
std::string err = tinyobj::LoadObj(shapes, col->m_geometry.m_meshFileName.c_str(),"",m_data->m_fileIO);
tinyobj::attrib_t attribute;
std::string err = tinyobj::LoadObj(attribute, shapes, col->m_geometry.m_meshFileName.c_str(), "", m_data->m_fileIO);
//create a convex hull for each shape, and store it in a btCompoundShape
childShape = MjcfCreateConvexHullFromShapes(shapes, col->m_geometry.m_meshScale, m_data->m_globalDefaults.m_defaultCollisionMargin);
childShape = MjcfCreateConvexHullFromShapes(attribute, shapes, col->m_geometry.m_meshScale, m_data->m_globalDefaults.m_defaultCollisionMargin);
}
break;
}

View File

@@ -65,13 +65,14 @@ bool b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(const std::string&
btVector3 shift(0, 0, 0);
std::vector<tinyobj::shape_t> shapes;
tinyobj::attrib_t attribute;
{
B3_PROFILE("tinyobj::LoadObj");
std::string err = LoadFromCachedOrFromObj(shapes, relativeFileName, pathPrefix,fileIO);
std::string err = LoadFromCachedOrFromObj(attribute, shapes, relativeFileName, pathPrefix, fileIO);
//std::string err = tinyobj::LoadObj(shapes, relativeFileName, pathPrefix);
}
GLInstanceGraphicsShape* gfxShape = btgCreateGraphicsShapeFromWavefrontObj(shapes);
GLInstanceGraphicsShape* gfxShape = btgCreateGraphicsShapeFromWavefrontObj(attribute, shapes);
{
B3_PROFILE("Load Texture");
//int textureIndex = -1;
@@ -84,7 +85,7 @@ bool b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(const std::string&
meshData.m_rgbaColor[2] = shape.material.diffuse[2];
meshData.m_rgbaColor[3] = shape.material.transparency;
meshData.m_flags |= B3_IMPORT_MESH_HAS_RGBA_COLOR;
meshData.m_specularColor[0] = shape.material.specular[0];
meshData.m_specularColor[1] = shape.material.specular[1];
meshData.m_specularColor[2] = shape.material.specular[2];

View File

@@ -12,6 +12,7 @@ struct CachedObjResult
{
std::string m_msg;
std::vector<tinyobj::shape_t> m_shapes;
tinyobj::attrib_t m_attribute;
};
static b3HashMap<b3HashString, CachedObjResult> gCachedObjResults;
@@ -31,24 +32,26 @@ void b3EnableFileCaching(int enable)
}
std::string LoadFromCachedOrFromObj(
tinyobj::attrib_t& attribute,
std::vector<tinyobj::shape_t>& shapes, // [output]
const char* filename,
const char* mtl_basepath,
struct CommonFileIOInterface* fileIO
)
struct CommonFileIOInterface* fileIO)
{
CachedObjResult* resultPtr = gCachedObjResults[filename];
if (resultPtr)
{
const CachedObjResult& result = *resultPtr;
shapes = result.m_shapes;
attribute = result.m_attribute;
return result.m_msg;
}
std::string err = tinyobj::LoadObj(shapes, filename, mtl_basepath,fileIO);
std::string err = tinyobj::LoadObj(attribute, shapes, filename, mtl_basepath, fileIO);
CachedObjResult result;
result.m_msg = err;
result.m_shapes = shapes;
result.m_attribute = attribute;
if (gEnableFileCaching)
{
gCachedObjResults.insert(filename, result);
@@ -60,14 +63,15 @@ GLInstanceGraphicsShape* LoadMeshFromObj(const char* relativeFileName, const cha
{
B3_PROFILE("LoadMeshFromObj");
std::vector<tinyobj::shape_t> shapes;
tinyobj::attrib_t attribute;
{
B3_PROFILE("tinyobj::LoadObj2");
std::string err = LoadFromCachedOrFromObj(shapes, relativeFileName, materialPrefixPath,fileIO);
std::string err = LoadFromCachedOrFromObj(attribute, shapes, relativeFileName, materialPrefixPath, fileIO);
}
{
B3_PROFILE("btgCreateGraphicsShapeFromWavefrontObj");
GLInstanceGraphicsShape* gfxShape = btgCreateGraphicsShapeFromWavefrontObj(shapes);
GLInstanceGraphicsShape* gfxShape = btgCreateGraphicsShapeFromWavefrontObj(attribute, shapes);
return gfxShape;
}
}

View File

@@ -8,8 +8,8 @@ struct GLInstanceGraphicsShape;
int b3IsFileCachingEnabled();
void b3EnableFileCaching(int enable);
std::string LoadFromCachedOrFromObj(
tinyobj::attrib_t& attribute,
std::vector<tinyobj::shape_t>& shapes, // [output]
const char* filename,
const char* mtl_basepath,

View File

@@ -9,7 +9,7 @@
#include "../../OpenGLWindow/GLInstancingRenderer.h"
#include "../../OpenGLWindow/GLInstanceGraphicsShape.h"
GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(std::vector<tinyobj::shape_t>& shapes, bool flatShading)
GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(const tinyobj::attrib_t& attribute, std::vector<tinyobj::shape_t>& shapes, bool flatShading)
{
b3AlignedObjectArray<GLInstanceVertex>* vertices = new b3AlignedObjectArray<GLInstanceVertex>;
{
@@ -36,19 +36,20 @@ GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(std::vector<tiny
}
GLInstanceVertex vtx0;
vtx0.xyzw[0] = shape.mesh.positions[shape.mesh.indices[f] * 3 + 0];
vtx0.xyzw[1] = shape.mesh.positions[shape.mesh.indices[f] * 3 + 1];
vtx0.xyzw[2] = shape.mesh.positions[shape.mesh.indices[f] * 3 + 2];
tinyobj::index_t v_0 = shape.mesh.indices[f];
vtx0.xyzw[0] = attribute.vertices[3 * v_0.vertex_index];
vtx0.xyzw[1] = attribute.vertices[3 * v_0.vertex_index + 1];
vtx0.xyzw[2] = attribute.vertices[3 * v_0.vertex_index + 2];
vtx0.xyzw[3] = 0.f;
if (shape.mesh.texcoords.size())
if (attribute.texcoords.size())
{
int uv0Index = shape.mesh.indices[f] * 2 + 0;
int uv1Index = shape.mesh.indices[f] * 2 + 1;
if (uv0Index >= 0 && uv1Index >= 0 && (uv0Index < int(shape.mesh.texcoords.size()) && (uv1Index < shape.mesh.texcoords.size())))
int uv0Index = 2 * v_0.texcoord_index;
int uv1Index = 2 * v_0.texcoord_index + 1;
if (uv0Index >= 0 && uv1Index >= 0 && (uv0Index < int(attribute.texcoords.size()) && (uv1Index < attribute.texcoords.size())))
{
vtx0.uv[0] = shape.mesh.texcoords[uv0Index];
vtx0.uv[1] = shape.mesh.texcoords[uv1Index];
vtx0.uv[0] = attribute.texcoords[uv0Index];
vtx0.uv[1] = attribute.texcoords[uv1Index];
}
else
{
@@ -64,19 +65,20 @@ GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(std::vector<tiny
}
GLInstanceVertex vtx1;
vtx1.xyzw[0] = shape.mesh.positions[shape.mesh.indices[f + 1] * 3 + 0];
vtx1.xyzw[1] = shape.mesh.positions[shape.mesh.indices[f + 1] * 3 + 1];
vtx1.xyzw[2] = shape.mesh.positions[shape.mesh.indices[f + 1] * 3 + 2];
tinyobj::index_t v_1 = shape.mesh.indices[f + 1];
vtx1.xyzw[0] = attribute.vertices[3 * v_1.vertex_index];
vtx1.xyzw[1] = attribute.vertices[3 * v_1.vertex_index + 1];
vtx1.xyzw[2] = attribute.vertices[3 * v_1.vertex_index + 2];
vtx1.xyzw[3] = 0.f;
if (shape.mesh.texcoords.size())
if (attribute.texcoords.size())
{
int uv0Index = shape.mesh.indices[f + 1] * 2 + 0;
int uv1Index = shape.mesh.indices[f + 1] * 2 + 1;
if (uv0Index >= 0 && uv1Index >= 0 && (uv0Index < shape.mesh.texcoords.size()) && (uv1Index < shape.mesh.texcoords.size()))
int uv0Index = 2 * v_1.texcoord_index;
int uv1Index = 2 * v_1.texcoord_index + 1;
if (uv0Index >= 0 && uv1Index >= 0 && (uv0Index < attribute.texcoords.size()) && (uv1Index < attribute.texcoords.size()))
{
vtx1.uv[0] = shape.mesh.texcoords[uv0Index];
vtx1.uv[1] = shape.mesh.texcoords[uv1Index];
vtx1.uv[0] = attribute.texcoords[uv0Index];
vtx1.uv[1] = attribute.texcoords[uv1Index];
}
else
{
@@ -92,18 +94,20 @@ GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(std::vector<tiny
}
GLInstanceVertex vtx2;
vtx2.xyzw[0] = shape.mesh.positions[shape.mesh.indices[f + 2] * 3 + 0];
vtx2.xyzw[1] = shape.mesh.positions[shape.mesh.indices[f + 2] * 3 + 1];
vtx2.xyzw[2] = shape.mesh.positions[shape.mesh.indices[f + 2] * 3 + 2];
tinyobj::index_t v_2 = shape.mesh.indices[f + 2];
vtx2.xyzw[0] = attribute.vertices[3 * v_2.vertex_index];
vtx2.xyzw[1] = attribute.vertices[3 * v_2.vertex_index + 1];
vtx2.xyzw[2] = attribute.vertices[3 * v_2.vertex_index + 2];
vtx2.xyzw[3] = 0.f;
if (shape.mesh.texcoords.size())
if (attribute.texcoords.size())
{
int uv0Index = shape.mesh.indices[f + 2] * 2 + 0;
int uv1Index = shape.mesh.indices[f + 2] * 2 + 1;
if (uv0Index >= 0 && uv1Index >= 0 && (uv0Index < shape.mesh.texcoords.size()) && (uv1Index < shape.mesh.texcoords.size()))
int uv0Index = 2 * v_2.texcoord_index;
int uv1Index = 2 * v_2.texcoord_index + 1;
if (uv0Index >= 0 && uv1Index >= 0 && (uv0Index < attribute.texcoords.size()) && (uv1Index < attribute.texcoords.size()))
{
vtx2.uv[0] = shape.mesh.texcoords[uv0Index];
vtx2.uv[1] = shape.mesh.texcoords[uv1Index];
vtx2.uv[0] = attribute.texcoords[uv0Index];
vtx2.uv[1] = attribute.texcoords[uv1Index];
}
else
{
@@ -123,16 +127,21 @@ GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(std::vector<tiny
btVector3 v2(vtx2.xyzw[0], vtx2.xyzw[1], vtx2.xyzw[2]);
unsigned int maxIndex = 0;
maxIndex = b3Max(maxIndex, shape.mesh.indices[f] * 3 + 0);
maxIndex = b3Max(maxIndex, shape.mesh.indices[f] * 3 + 1);
maxIndex = b3Max(maxIndex, shape.mesh.indices[f] * 3 + 2);
maxIndex = b3Max(maxIndex, shape.mesh.indices[f + 1] * 3 + 0);
maxIndex = b3Max(maxIndex, shape.mesh.indices[f + 1] * 3 + 1);
maxIndex = b3Max(maxIndex, shape.mesh.indices[f + 1] * 3 + 2);
maxIndex = b3Max(maxIndex, shape.mesh.indices[f + 2] * 3 + 0);
maxIndex = b3Max(maxIndex, shape.mesh.indices[f + 2] * 3 + 1);
maxIndex = b3Max(maxIndex, shape.mesh.indices[f + 2] * 3 + 2);
bool hasNormals = (shape.mesh.normals.size() && maxIndex < shape.mesh.normals.size());
unsigned n0Index = shape.mesh.indices[f].normal_index;
unsigned n1Index = shape.mesh.indices[f + 1].normal_index;
unsigned n2Index = shape.mesh.indices[f + 2].normal_index;
maxIndex = b3Max(maxIndex, 3 * n0Index + 0);
maxIndex = b3Max(maxIndex, 3 * n0Index + 1);
maxIndex = b3Max(maxIndex, 3 * n0Index + 2);
maxIndex = b3Max(maxIndex, 3 * n1Index + 0);
maxIndex = b3Max(maxIndex, 3 * n1Index + 1);
maxIndex = b3Max(maxIndex, 3 * n1Index + 2);
maxIndex = b3Max(maxIndex, 3 * n2Index + 0);
maxIndex = b3Max(maxIndex, 3 * n2Index + 1);
maxIndex = b3Max(maxIndex, 3 * n2Index + 2);
bool hasNormals = (attribute.normals.size() && maxIndex < attribute.normals.size());
if (flatShading || !hasNormals)
{
@@ -159,15 +168,15 @@ GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(std::vector<tiny
}
else
{
vtx0.normal[0] = shape.mesh.normals[shape.mesh.indices[f] * 3 + 0];
vtx0.normal[1] = shape.mesh.normals[shape.mesh.indices[f] * 3 + 1];
vtx0.normal[2] = shape.mesh.normals[shape.mesh.indices[f] * 3 + 2]; //shape.mesh.indices[f+1]*3+0
vtx1.normal[0] = shape.mesh.normals[shape.mesh.indices[f + 1] * 3 + 0];
vtx1.normal[1] = shape.mesh.normals[shape.mesh.indices[f + 1] * 3 + 1];
vtx1.normal[2] = shape.mesh.normals[shape.mesh.indices[f + 1] * 3 + 2];
vtx2.normal[0] = shape.mesh.normals[shape.mesh.indices[f + 2] * 3 + 0];
vtx2.normal[1] = shape.mesh.normals[shape.mesh.indices[f + 2] * 3 + 1];
vtx2.normal[2] = shape.mesh.normals[shape.mesh.indices[f + 2] * 3 + 2];
vtx0.normal[0] = attribute.normals[3 * n0Index+ 0];
vtx0.normal[1] = attribute.normals[3 * n0Index+ 1];
vtx0.normal[2] = attribute.normals[3 * n0Index+ 2];
vtx1.normal[0] = attribute.normals[3 * n1Index+ 0];
vtx1.normal[1] = attribute.normals[3 * n1Index+ 1];
vtx1.normal[2] = attribute.normals[3 * n1Index+ 2];
vtx2.normal[0] = attribute.normals[3 * n2Index+ 0];
vtx2.normal[1] = attribute.normals[3 * n2Index+ 1];
vtx2.normal[2] = attribute.normals[3 * n2Index+ 2];
}
vertices->push_back(vtx0);
vertices->push_back(vtx1);

View File

@@ -4,6 +4,6 @@
#include "../../ThirdPartyLibs/Wavefront/tiny_obj_loader.h"
#include <vector>
struct GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(std::vector<tinyobj::shape_t>& shapes, bool flatShading = false);
struct GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(const tinyobj::attrib_t& attribute, std::vector<tinyobj::shape_t>& shapes, bool flatShading = false);
#endif //WAVEFRONT2GRAPHICS_H

View File

@@ -509,7 +509,7 @@ bool BulletURDFImporter::getRootTransformInWorld(btTransform& rootTransformInWor
return true;
}
static btCollisionShape* createConvexHullFromShapes(std::vector<tinyobj::shape_t>& shapes, const btVector3& geomScale, int flags)
static btCollisionShape* createConvexHullFromShapes(const tinyobj::attrib_t& attribute, std::vector<tinyobj::shape_t>& shapes, const btVector3& geomScale, int flags)
{
B3_PROFILE("createConvexHullFromShapes");
btCompoundShape* compound = new btCompoundShape();
@@ -528,20 +528,20 @@ static btCollisionShape* createConvexHullFromShapes(std::vector<tinyobj::shape_t
for (int f = 0; f < faceCount; f += 3)
{
btVector3 pt;
pt.setValue(shape.mesh.positions[shape.mesh.indices[f] * 3 + 0],
shape.mesh.positions[shape.mesh.indices[f] * 3 + 1],
shape.mesh.positions[shape.mesh.indices[f] * 3 + 2]);
pt.setValue(attribute.vertices[3 * shape.mesh.indices[f + 0].vertex_index + 0],
attribute.vertices[3 * shape.mesh.indices[f + 0].vertex_index + 1],
attribute.vertices[3 * shape.mesh.indices[f + 0].vertex_index + 2]);
convexHull->addPoint(pt * geomScale, false);
pt.setValue(shape.mesh.positions[shape.mesh.indices[f + 1] * 3 + 0],
shape.mesh.positions[shape.mesh.indices[f + 1] * 3 + 1],
shape.mesh.positions[shape.mesh.indices[f + 1] * 3 + 2]);
pt.setValue(attribute.vertices[3 * shape.mesh.indices[f + 1].vertex_index + 0],
attribute.vertices[3 * shape.mesh.indices[f + 1].vertex_index + 1],
attribute.vertices[3 * shape.mesh.indices[f + 1].vertex_index + 2]);
convexHull->addPoint(pt * geomScale, false);
pt.setValue(shape.mesh.positions[shape.mesh.indices[f + 2] * 3 + 0],
shape.mesh.positions[shape.mesh.indices[f + 2] * 3 + 1],
shape.mesh.positions[shape.mesh.indices[f + 2] * 3 + 2]);
pt.setValue(attribute.vertices[3 * shape.mesh.indices[f + 2].vertex_index + 0],
attribute.vertices[3 * shape.mesh.indices[f + 2].vertex_index + 1],
attribute.vertices[3 * shape.mesh.indices[f + 2].vertex_index + 2]);
convexHull->addPoint(pt * geomScale, false);
}
@@ -558,8 +558,6 @@ static btCollisionShape* createConvexHullFromShapes(std::vector<tinyobj::shape_t
return compound;
}
int BulletURDFImporter::getUrdfFromCollisionShape(const btCollisionShape* collisionShape, UrdfCollision& collision) const
{
UrdfCollision* col = m_data->m_bulletCollisionShape2UrdfCollision.find(collisionShape);
@@ -718,10 +716,10 @@ btCollisionShape* BulletURDFImporter::convertURDFToCollisionShape(const UrdfColl
else
{
std::vector<tinyobj::shape_t> shapes;
std::string err = tinyobj::LoadObj(shapes, collision->m_geometry.m_meshFileName.c_str(),"",m_data->m_fileIO);
tinyobj::attrib_t attribute;
std::string err = tinyobj::LoadObj(attribute, shapes, collision->m_geometry.m_meshFileName.c_str(), "", m_data->m_fileIO);
//create a convex hull for each shape, and store it in a btCompoundShape
shape = createConvexHullFromShapes(shapes, collision->m_geometry.m_meshScale, m_data->m_flags);
shape = createConvexHullFromShapes(attribute, shapes, collision->m_geometry.m_meshScale, m_data->m_flags);
m_data->m_bulletCollisionShape2UrdfCollision.insert(shape, *collision);
return shape;
}

View File

@@ -0,0 +1,358 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
///create 125 (5x5x5) dynamic object
#define ARRAY_SIZE_X 5
#define ARRAY_SIZE_Y 5
#define ARRAY_SIZE_Z 5
//maximum number of objects (and allow user to shoot additional boxes)
#define MAX_PROXIES (ARRAY_SIZE_X * ARRAY_SIZE_Y * ARRAY_SIZE_Z + 1024)
///scaling of the objects (0.1 = 20 centimeter boxes )
#define SCALING 1.
#define START_POS_X -5
#define START_POS_Y -5
#define START_POS_Z -3
#include "MultiBodyBaseline.h"
///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files.
#include "btBulletDynamicsCommon.h"
#include "BulletSoftBody/btDeformableRigidDynamicsWorld.h"
#include "BulletSoftBody/btSoftBody.h"
#include "BulletSoftBody/btSoftBodyHelpers.h"
#include "BulletSoftBody/btDeformableBodySolver.h"
#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h"
#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h"
#include <stdio.h> //printf debugging
#include "../CommonInterfaces/CommonRigidBodyBase.h"
#include "../Utils/b3ResourcePath.h"
#include "../SoftDemo/BunnyMesh.h"
#include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h"
#include "BulletDynamics/Featherstone/btMultiBodyJointFeedback.h"
#include "../CommonInterfaces/CommonMultiBodyBase.h"
#include "../Utils/b3ResourcePath.h"
///The MultiBodyBaseline demo deformable bodies self-collision
static bool g_floatingBase = true;
static float friction = 1.;
class MultiBodyBaseline : public CommonMultiBodyBase
{
btMultiBody* m_multiBody;
btAlignedObjectArray<btMultiBodyJointFeedback*> m_jointFeedbacks;
public:
MultiBodyBaseline(struct GUIHelperInterface* helper)
: CommonMultiBodyBase(helper)
{
}
virtual ~MultiBodyBaseline()
{
}
void initPhysics();
void exitPhysics();
void resetCamera()
{
float dist = 30;
float pitch = -30;
float yaw = 100;
float targetPos[3] = {0, -10, 0};
m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]);
}
virtual void stepSimulation(float deltaTime);
btMultiBody* createFeatherstoneMultiBody_testMultiDof(class btMultiBodyDynamicsWorld* world, int numLinks, const btVector3& basePosition, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents, bool spherical = false, bool floating = false);
void addColliders_testMultiDof(btMultiBody* pMultiBody, btMultiBodyDynamicsWorld* pWorld, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents);
};
void MultiBodyBaseline::initPhysics()
{
m_guiHelper->setUpAxis(1);
///collision configuration contains default setup for memory, collision setup
m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration();
///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded)
m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration);
m_broadphase = new btDbvtBroadphase();
btMultiBodyConstraintSolver* sol;
sol = new btMultiBodyConstraintSolver;
m_solver = sol;
btMultiBodyDynamicsWorld* world = new btMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration);
m_dynamicsWorld = world;
// m_dynamicsWorld->setDebugDrawer(&gDebugDraw);
m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld);
m_dynamicsWorld->setGravity(btVector3(0, -10, 0));
{
///create a ground
btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(150.), btScalar(25.), btScalar(150.)));
m_collisionShapes.push_back(groundShape);
btTransform groundTransform;
groundTransform.setIdentity();
groundTransform.setOrigin(btVector3(0, -40, 0));
groundTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0.));
//We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here:
btScalar mass(0.);
//rigidbody is dynamic if and only if mass is non zero, otherwise static
bool isDynamic = (mass != 0.f);
btVector3 localInertia(0, 0, 0);
if (isDynamic)
groundShape->calculateLocalInertia(mass, localInertia);
//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform);
btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia);
btRigidBody* body = new btRigidBody(rbInfo);
body->setFriction(0.5);
//add the ground to the dynamics world
m_dynamicsWorld->addRigidBody(body,1,1+2);
}
{
bool damping = true;
bool gyro = false;
int numLinks = 4;
bool spherical = false; //set it ot false -to use 1DoF hinges instead of 3DoF sphericals
bool canSleep = false;
bool selfCollide = true;
btVector3 linkHalfExtents(1, 1, 1);
btVector3 baseHalfExtents(1, 1, 1);
btMultiBody* mbC = createFeatherstoneMultiBody_testMultiDof(m_dynamicsWorld, numLinks, btVector3(0.f, 10.f,0.f), linkHalfExtents, baseHalfExtents, spherical, g_floatingBase);
mbC->setCanSleep(canSleep);
mbC->setHasSelfCollision(selfCollide);
mbC->setUseGyroTerm(gyro);
//
if (!damping)
{
mbC->setLinearDamping(0.0f);
mbC->setAngularDamping(0.0f);
}
else
{
mbC->setLinearDamping(0.04f);
mbC->setAngularDamping(0.04f);
}
if (numLinks > 0)
{
btScalar q0 = 0.f * SIMD_PI / 180.f;
if (!spherical)
{
mbC->setJointPosMultiDof(0, &q0);
}
else
{
btQuaternion quat0(btVector3(1, 1, 0).normalized(), q0);
quat0.normalize();
mbC->setJointPosMultiDof(0, quat0);
}
}
///
addColliders_testMultiDof(mbC, m_dynamicsWorld, baseHalfExtents, linkHalfExtents);
}
m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
}
void MultiBodyBaseline::exitPhysics()
{
//cleanup in the reverse order of creation/initialization
//remove the rigidbodies from the dynamics world and delete them
int i;
for (i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--)
{
btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i];
btRigidBody* body = btRigidBody::upcast(obj);
if (body && body->getMotionState())
{
delete body->getMotionState();
}
m_dynamicsWorld->removeCollisionObject(obj);
delete obj;
}
//delete collision shapes
for (int j = 0; j < m_collisionShapes.size(); j++)
{
btCollisionShape* shape = m_collisionShapes[j];
delete shape;
}
m_collisionShapes.clear();
delete m_dynamicsWorld;
delete m_solver;
delete m_broadphase;
delete m_dispatcher;
delete m_collisionConfiguration;
}
void MultiBodyBaseline::stepSimulation(float deltaTime)
{
// getDeformableDynamicsWorld()->getMultiBodyDynamicsWorld()->stepSimulation(deltaTime);
m_dynamicsWorld->stepSimulation(deltaTime, 5, 1./250.);
}
btMultiBody* MultiBodyBaseline::createFeatherstoneMultiBody_testMultiDof(btMultiBodyDynamicsWorld* pWorld, int numLinks, const btVector3& basePosition, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents, bool spherical, bool floating)
{
//init the base
btVector3 baseInertiaDiag(0.f, 0.f, 0.f);
float baseMass = .1f;
if (baseMass)
{
btCollisionShape* pTempBox = new btBoxShape(btVector3(baseHalfExtents[0], baseHalfExtents[1], baseHalfExtents[2]));
pTempBox->calculateLocalInertia(baseMass, baseInertiaDiag);
delete pTempBox;
}
bool canSleep = false;
btMultiBody* pMultiBody = new btMultiBody(numLinks, baseMass, baseInertiaDiag, !floating, canSleep);
btQuaternion baseOriQuat(0.f, 0.f, 0.f, 1.f);
pMultiBody->setBasePos(basePosition);
pMultiBody->setWorldToBaseRot(baseOriQuat);
btVector3 vel(0, 0, 0);
// pMultiBody->setBaseVel(vel);
//init the links
btVector3 hingeJointAxis(1, 0, 0);
float linkMass = .1f;
btVector3 linkInertiaDiag(0.f, 0.f, 0.f);
btCollisionShape* pTempBox = new btBoxShape(btVector3(linkHalfExtents[0], linkHalfExtents[1], linkHalfExtents[2]));
pTempBox->calculateLocalInertia(linkMass, linkInertiaDiag);
delete pTempBox;
//y-axis assumed up
btVector3 parentComToCurrentCom(0, -linkHalfExtents[1] * 2.f, 0); //par body's COM to cur body's COM offset
btVector3 currentPivotToCurrentCom(0, -linkHalfExtents[1], 0); //cur body's COM to cur body's PIV offset
btVector3 parentComToCurrentPivot = parentComToCurrentCom - currentPivotToCurrentCom; //par body's COM to cur body's PIV offset
//////
btScalar q0 = 0.f * SIMD_PI / 180.f;
btQuaternion quat0(btVector3(0, 1, 0).normalized(), q0);
quat0.normalize();
/////
for (int i = 0; i < numLinks; ++i)
{
if (!spherical)
pMultiBody->setupRevolute(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f), hingeJointAxis, parentComToCurrentPivot, currentPivotToCurrentCom, true);
else
//pMultiBody->setupPlanar(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f)/*quat0*/, btVector3(1, 0, 0), parentComToCurrentPivot*2, false);
pMultiBody->setupSpherical(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f), parentComToCurrentPivot, currentPivotToCurrentCom, true);
}
pMultiBody->finalizeMultiDof();
///
pWorld->addMultiBody(pMultiBody);
///
return pMultiBody;
}
void MultiBodyBaseline::addColliders_testMultiDof(btMultiBody* pMultiBody, btMultiBodyDynamicsWorld* pWorld, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents)
{
btAlignedObjectArray<btQuaternion> world_to_local;
world_to_local.resize(pMultiBody->getNumLinks() + 1);
btAlignedObjectArray<btVector3> local_origin;
local_origin.resize(pMultiBody->getNumLinks() + 1);
world_to_local[0] = pMultiBody->getWorldToBaseRot();
local_origin[0] = pMultiBody->getBasePos();
{
// float pos[4]={local_origin[0].x(),local_origin[0].y(),local_origin[0].z(),1};
btScalar quat[4] = {-world_to_local[0].x(), -world_to_local[0].y(), -world_to_local[0].z(), world_to_local[0].w()};
if (1)
{
btCollisionShape* box = new btBoxShape(baseHalfExtents);
btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(pMultiBody, -1);
col->setCollisionShape(box);
btTransform tr;
tr.setIdentity();
tr.setOrigin(local_origin[0]);
tr.setRotation(btQuaternion(quat[0], quat[1], quat[2], quat[3]));
col->setWorldTransform(tr);
pWorld->addCollisionObject(col, 2, 1 + 2);
col->setFriction(friction);
pMultiBody->setBaseCollider(col);
}
}
for (int i = 0; i < pMultiBody->getNumLinks(); ++i)
{
const int parent = pMultiBody->getParent(i);
world_to_local[i + 1] = pMultiBody->getParentToLocalRot(i) * world_to_local[parent + 1];
local_origin[i + 1] = local_origin[parent + 1] + (quatRotate(world_to_local[i + 1].inverse(), pMultiBody->getRVector(i)));
}
for (int i = 0; i < pMultiBody->getNumLinks(); ++i)
{
btVector3 posr = local_origin[i + 1];
// float pos[4]={posr.x(),posr.y(),posr.z(),1};
btScalar quat[4] = {-world_to_local[i + 1].x(), -world_to_local[i + 1].y(), -world_to_local[i + 1].z(), world_to_local[i + 1].w()};
btCollisionShape* box = new btBoxShape(linkHalfExtents);
btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(pMultiBody, i);
col->setCollisionShape(box);
btTransform tr;
tr.setIdentity();
tr.setOrigin(posr);
tr.setRotation(btQuaternion(quat[0], quat[1], quat[2], quat[3]));
col->setWorldTransform(tr);
col->setFriction(friction);
pWorld->addCollisionObject(col, 2, 1 + 2);
pMultiBody->getLink(i).m_collider = col;
}
}
class CommonExampleInterface* MultiBodyBaselineCreateFunc(struct CommonExampleOptions& options)
{
return new MultiBodyBaseline(options.m_guiHelper);
}

View File

@@ -0,0 +1,20 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef _MULTIBODY_BASELINE_H
#define _MULTIBODY_BASELINE_H
class CommonExampleInterface* MultiBodyBaselineCreateFunc(struct CommonExampleOptions& options);
#endif //_MULTIBODY_BASELINE_H

View File

@@ -4861,7 +4861,8 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str
else
{
std::vector<tinyobj::shape_t> shapes;
std::string err = tinyobj::LoadObj(shapes, out_found_filename.c_str(),"",fileIO);
tinyobj::attrib_t attribute;
std::string err = tinyobj::LoadObj(attribute, shapes, out_found_filename.c_str(), "", fileIO);
//shape = createConvexHullFromShapes(shapes, collision->m_geometry.m_meshScale);
//static btCollisionShape* createConvexHullFromShapes(std::vector<tinyobj::shape_t>& shapes, const btVector3& geomScale)
@@ -4882,20 +4883,20 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str
for (int f = 0; f < faceCount; f += 3)
{
btVector3 pt;
pt.setValue(shape.mesh.positions[shape.mesh.indices[f] * 3 + 0],
shape.mesh.positions[shape.mesh.indices[f] * 3 + 1],
shape.mesh.positions[shape.mesh.indices[f] * 3 + 2]);
pt.setValue(attribute.vertices[3 * shape.mesh.indices[f + 0].vertex_index + 0],
attribute.vertices[3 * shape.mesh.indices[f + 0].vertex_index + 1],
attribute.vertices[3 * shape.mesh.indices[f + 0].vertex_index + 2]);
convexHull->addPoint(pt * meshScale, false);
pt.setValue(shape.mesh.positions[shape.mesh.indices[f + 1] * 3 + 0],
shape.mesh.positions[shape.mesh.indices[f + 1] * 3 + 1],
shape.mesh.positions[shape.mesh.indices[f + 1] * 3 + 2]);
pt.setValue(attribute.vertices[3 * shape.mesh.indices[f + 1].vertex_index + 0],
attribute.vertices[3 * shape.mesh.indices[f + 1].vertex_index + 1],
attribute.vertices[3 * shape.mesh.indices[f + 1].vertex_index + 2]);
convexHull->addPoint(pt * meshScale, false);
pt.setValue(shape.mesh.positions[shape.mesh.indices[f + 2] * 3 + 0],
shape.mesh.positions[shape.mesh.indices[f + 2] * 3 + 1],
shape.mesh.positions[shape.mesh.indices[f + 2] * 3 + 2]);
pt.setValue(attribute.vertices[3 * shape.mesh.indices[f + 2].vertex_index + 0],
attribute.vertices[3 * shape.mesh.indices[f + 2].vertex_index + 1],
attribute.vertices[3 * shape.mesh.indices[f + 2].vertex_index + 2]);
convexHull->addPoint(pt * meshScale, false);
}
@@ -7958,8 +7959,8 @@ bool PhysicsServerCommandProcessor::processLoadSoftBodyCommand(const struct Shar
serverStatusOut.m_type = CMD_LOAD_SOFT_BODY_FAILED;
bool hasStatus = true;
#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
double scale = 0.1;
double mass = 0.1;
double scale = 1;
double mass = 1;
double collisionMargin = 0.02;
const LoadSoftBodyArgs& loadSoftBodyArgs = clientCmd.m_loadSoftBodyArguments;
if (m_data->m_verboseOutput)
@@ -8012,23 +8013,24 @@ bool PhysicsServerCommandProcessor::processLoadSoftBodyCommand(const struct Shar
std::string out_found_filename;
int out_type;
bool foundFile = UrdfFindMeshFile(fileIO,pathPrefix, relativeFileName, error_message_prefix, &out_found_filename, &out_type);
bool foundFile = UrdfFindMeshFile(fileIO, pathPrefix, relativeFileName, error_message_prefix, &out_found_filename, &out_type);
std::vector<tinyobj::shape_t> shapes;
std::string err = tinyobj::LoadObj(shapes, out_found_filename.c_str(),"",fileIO);
tinyobj::attrib_t attribute;
std::string err = tinyobj::LoadObj(attribute, shapes, out_found_filename.c_str(), "", fileIO);
if (!shapes.empty())
{
const tinyobj::shape_t& shape = shapes[0];
btAlignedObjectArray<btScalar> vertices;
btAlignedObjectArray<int> indices;
for (int i = 0; i < shape.mesh.positions.size(); i++)
for (int i = 0; i < attribute.vertices.size(); i++)
{
vertices.push_back(shape.mesh.positions[i]);
vertices.push_back(attribute.vertices[i]);
}
for (int i = 0; i < shape.mesh.indices.size(); i++)
{
indices.push_back(shape.mesh.indices[i]);
indices.push_back(shape.mesh.indices[i].vertex_index);
}
int numTris = indices.size() / 3;
int numTris = shape.mesh.indices.size() / 3;
if (numTris > 0)
{
btSoftBody* psb = btSoftBodyHelpers::CreateFromTriMesh(m_data->m_dynamicsWorld->getWorldInfo(), &vertices[0], &indices[0], numTris);
@@ -8041,9 +8043,9 @@ bool PhysicsServerCommandProcessor::processLoadSoftBodyCommand(const struct Shar
//turn on softbody vs softbody collision
psb->m_cfg.collisions |= btSoftBody::fCollision::VF_SS;
psb->randomizeConstraints();
psb->scale(btVector3(scale, scale, scale));
psb->rotate(initialOrn);
psb->translate(initialPos);
psb->scale(btVector3(scale, scale, scale));
psb->setTotalMass(mass, true);
psb->getCollisionShape()->setMargin(collisionMargin);

View File

@@ -38,51 +38,102 @@ Licensed under 2 clause BSD.
Usage
-----
Data format
attrib_t contains single and linear array of vertex data(position, normal and texcoord).
std::string inputfile = "cornell_box.obj";
std::vector<tinyobj::shape_t> shapes;
std::string err = tinyobj::LoadObj(shapes, inputfile.c_str());
if (!err.empty()) {
std::cerr << err << std::endl;
exit(1);
}
std::cout << "# of shapes : " << shapes.size() << std::endl;
for (size_t i = 0; i < shapes.size(); i++) {
printf("shape[%ld].name = %s\n", i, shapes[i].name.c_str());
printf("shape[%ld].indices: %ld\n", i, shapes[i].mesh.indices.size());
assert((shapes[i].mesh.indices.size() % 3) == 0);
for (size_t f = 0; f < shapes[i].mesh.indices.size(); f++) {
printf(" idx[%ld] = %d\n", f, shapes[i].mesh.indices[f]);
}
printf("shape[%ld].vertices: %ld\n", i, shapes[i].mesh.positions.size());
assert((shapes[i].mesh.positions.size() % 3) == 0);
for (size_t v = 0; v < shapes[i].mesh.positions.size() / 3; v++) {
printf(" v[%ld] = (%f, %f, %f)\n", v,
shapes[i].mesh.positions[3*v+0],
shapes[i].mesh.positions[3*v+1],
shapes[i].mesh.positions[3*v+2]);
}
printf("shape[%ld].material.name = %s\n", i, shapes[i].material.name.c_str());
printf(" material.Ka = (%f, %f ,%f)\n", shapes[i].material.ambient[0], shapes[i].material.ambient[1], shapes[i].material.ambient[2]);
printf(" material.Kd = (%f, %f ,%f)\n", shapes[i].material.diffuse[0], shapes[i].material.diffuse[1], shapes[i].material.diffuse[2]);
printf(" material.Ks = (%f, %f ,%f)\n", shapes[i].material.specular[0], shapes[i].material.specular[1], shapes[i].material.specular[2]);
printf(" material.Tr = (%f, %f ,%f)\n", shapes[i].material.transmittance[0], shapes[i].material.transmittance[1], shapes[i].material.transmittance[2]);
printf(" material.Ke = (%f, %f ,%f)\n", shapes[i].material.emission[0], shapes[i].material.emission[1], shapes[i].material.emission[2]);
printf(" material.Ns = %f\n", shapes[i].material.shininess);
printf(" material.map_Ka = %s\n", shapes[i].material.ambient_texname.c_str());
printf(" material.map_Kd = %s\n", shapes[i].material.diffuse_texname.c_str());
printf(" material.map_Ks = %s\n", shapes[i].material.specular_texname.c_str());
printf(" material.map_Ns = %s\n", shapes[i].material.normal_texname.c_str());
std::map<std::string, std::string>::iterator it(shapes[i].material.unknown_parameter.begin());
std::map<std::string, std::string>::iterator itEnd(shapes[i].material.unknown_parameter.end());
for (; it != itEnd; it++) {
printf(" material.%s = %s\n", it->first.c_str(), it->second.c_str());
}
printf("\n");
attrib_t::vertices => 3 floats per vertex
v[0] v[1] v[2] v[3] v[n-1]
+-----------+-----------+-----------+-----------+ +-----------+
| x | y | z | x | y | z | x | y | z | x | y | z | .... | x | y | z |
+-----------+-----------+-----------+-----------+ +-----------+
attrib_t::normals => 3 floats per vertex
n[0] n[1] n[2] n[3] n[n-1]
+-----------+-----------+-----------+-----------+ +-----------+
| x | y | z | x | y | z | x | y | z | x | y | z | .... | x | y | z |
+-----------+-----------+-----------+-----------+ +-----------+
attrib_t::texcoords => 2 floats per vertex
t[0] t[1] t[2] t[3] t[n-1]
+-----------+-----------+-----------+-----------+ +-----------+
| u | v | u | v | u | v | u | v | .... | u | v |
+-----------+-----------+-----------+-----------+ +-----------+
attrib_t::colors => 3 floats per vertex(vertex color. optional)
c[0] c[1] c[2] c[3] c[n-1]
+-----------+-----------+-----------+-----------+ +-----------+
| x | y | z | x | y | z | x | y | z | x | y | z | .... | x | y | z |
+-----------+-----------+-----------+-----------+ +-----------+
Each shape_t::mesh_t does not contain vertex data but contains array index to attrib_t. See loader_example.cc for more details.
mesh_t::indices => array of vertex indices.
+----+----+----+----+----+----+----+----+----+----+ +--------+
| i0 | i1 | i2 | i3 | i4 | i5 | i6 | i7 | i8 | i9 | ... | i(n-1) |
+----+----+----+----+----+----+----+----+----+----+ +--------+
Each index has an array index to attrib_t::vertices, attrib_t::normals and attrib_t::texcoords.
mesh_t::num_face_vertices => array of the number of vertices per face(e.g. 3 = triangle, 4 = quad , 5 or more = N-gons).
+---+---+---+ +---+
| 3 | 4 | 3 | ...... | 3 |
+---+---+---+ +---+
| | | |
| | | +-----------------------------------------+
| | | |
| | +------------------------------+ |
| | | |
| +------------------+ | |
| | | |
|/ |/ |/ |/
mesh_t::indices
| face[0] | face[1] | face[2] | | face[n-1] |
+----+----+----+----+----+----+----+----+----+----+ +--------+--------+--------+
| i0 | i1 | i2 | i3 | i4 | i5 | i6 | i7 | i8 | i9 | ... | i(n-3) | i(n-2) | i(n-1) |
+----+----+----+----+----+----+----+----+----+----+ +--------+--------+--------+
```c++
#define TINYOBJLOADER_IMPLEMENTATION // define this in only *one* .cc
#include "tiny_obj_loader.h"
std::string inputfile = "cornell_box.obj";
tinyobj::attrib_t attrib;
std::vector<tinyobj::shape_t> shapes;
LoadObj(attrib, shapes, inputfile.c_str());
// Loop over shapes
for (size_t s = 0; s < shapes.size(); s++) {
// Loop over faces(polygon)
size_t index_offset = 0;
for (size_t f = 0; f < shapes[s].mesh.indices.size(); f++) {
int fv = 3;
// Loop over vertices in the face.
for (size_t v = 0; v < fv; v++) {
// access to vertex
tinyobj::index_t idx = shapes[s].mesh.indices[index_offset + v];
tinyobj::real_t vx = attrib.vertices[3*idx.vertex_index+0];
tinyobj::real_t vy = attrib.vertices[3*idx.vertex_index+1];
tinyobj::real_t vz = attrib.vertices[3*idx.vertex_index+2];
tinyobj::real_t nx = attrib.normals[3*idx.normal_index+0];
tinyobj::real_t ny = attrib.normals[3*idx.normal_index+1];
tinyobj::real_t nz = attrib.normals[3*idx.normal_index+2];
tinyobj::real_t tx = attrib.texcoords[2*idx.texcoord_index+0];
tinyobj::real_t ty = attrib.texcoords[2*idx.texcoord_index+1];
}
index_offset += fv;
}
}
```

View File

@@ -70,25 +70,6 @@ std::istream& safeGetline(std::istream& is, std::string& t)
}
}
#endif
struct vertex_index
{
int v_idx, vt_idx, vn_idx, dummy;
};
struct MyIndices
{
int m_offset;
int m_numIndices;
};
// for std::map
static inline bool operator<(const vertex_index& a, const vertex_index& b)
{
if (a.v_idx != b.v_idx) return (a.v_idx < b.v_idx);
if (a.vn_idx != b.vn_idx) return (a.vn_idx < b.vn_idx);
if (a.vt_idx != b.vt_idx) return (a.vt_idx < b.vt_idx);
return false;
}
static inline bool isSpace(const char c)
{
@@ -101,25 +82,33 @@ static inline bool isNewLine(const char c)
}
// Make index zero-base, and also support relative index.
static inline int fixIndex(int idx, int n)
static inline bool fixIndex(int idx, int n, int* ret)
{
int i;
if (!ret)
{
return false;
}
if (idx > 0)
{
i = idx - 1;
(*ret) = idx - 1;
return true;
}
else if (idx == 0)
{
i = 0;
}
else
{ // negative value = relative
i = n + idx;
}
return i;
}
if (idx == 0)
{
// zero is not allowed according to the spec.
return false;
}
if (idx < 0)
{
(*ret) = n + idx; // negative value = relative
return true;
}
return false; // never reach here.
}
static inline std::string parseString(const char*& token)
{
std::string s;
@@ -156,170 +145,184 @@ static inline void parseFloat3(
z = parseFloat(token);
}
// Parse triples: i, i/j/k, i//k, i/j
static vertex_index parseTriple(
const char*& token,
int vsize,
int vnsize,
int vtsize)
// Parse triples with index offsets: i, i/j/k, i//k, i/j
static bool parseTriple(const char** token, int vsize, int vnsize, int vtsize,
vertex_index_t* ret)
{
vertex_index vi;
vi.vn_idx = -1;
vi.vt_idx = -1;
vi.v_idx = -1;
vi.v_idx = fixIndex(atoi(token), vsize);
token += strcspn(token, "/ \t\r");
if (token[0] != '/')
{
return vi;
}
token++;
// i//k
if (token[0] == '/')
{
token++;
vi.vn_idx = fixIndex(atoi(token), vnsize);
token += strcspn(token, "/ \t\r");
return vi;
}
// i/j/k or i/j
vi.vt_idx = fixIndex(atoi(token), vtsize);
token += strcspn(token, "/ \t\r");
if (token[0] != '/')
{
return vi;
}
// i/j/k
token++; // skip '/'
vi.vn_idx = fixIndex(atoi(token), vnsize);
token += strcspn(token, "/ \t\r");
return vi;
}
static unsigned int
updateVertex(
std::map<vertex_index, unsigned int>& vertexCache,
std::vector<float>& positions,
std::vector<float>& normals,
std::vector<float>& texcoords,
const std::vector<float>& in_positions,
const std::vector<float>& in_normals,
const std::vector<float>& in_texcoords,
const vertex_index& i)
{
const std::map<vertex_index, unsigned int>::iterator it = vertexCache.find(i);
if (it != vertexCache.end())
{
// found cache
return it->second;
}
assert(static_cast<int>(in_positions.size()) > (3 * i.v_idx + 2));
positions.push_back(in_positions[3 * i.v_idx + 0]);
positions.push_back(in_positions[3 * i.v_idx + 1]);
positions.push_back(in_positions[3 * i.v_idx + 2]);
if (i.vn_idx >= 0 && ((3 * i.vn_idx + 2) < in_normals.size()))
{
normals.push_back(in_normals[3 * i.vn_idx + 0]);
normals.push_back(in_normals[3 * i.vn_idx + 1]);
normals.push_back(in_normals[3 * i.vn_idx + 2]);
}
if (i.vt_idx >= 0)
{
int numTexCoords = in_texcoords.size();
int index0 = 2 * i.vt_idx + 0;
int index1 = 2 * i.vt_idx + 1;
if (index0 >= 0 && (index0) < numTexCoords)
{
texcoords.push_back(in_texcoords[index0]);
}
if (index1 >= 0 && (index1) < numTexCoords)
{
texcoords.push_back(in_texcoords[index1]);
}
}
unsigned int idx = positions.size() / 3 - 1;
vertexCache[i] = idx;
return idx;
}
static bool
exportFaceGroupToShape(
shape_t& shape,
const std::vector<float>& in_positions,
const std::vector<float>& in_normals,
const std::vector<float>& in_texcoords,
const std::vector<MyIndices>& faceGroup,
const material_t material,
const std::string name,
std::vector<vertex_index>& allIndices)
{
if (faceGroup.empty())
if (!ret)
{
return false;
}
vertex_index_t vi(-1);
if (!fixIndex(atoi((*token)), vsize, &(vi.v_idx)))
{
return false;
}
(*token) += strcspn((*token), "/ \t\r");
if ((*token)[0] != '/')
{
(*ret) = vi;
return true;
}
(*token)++;
// i//k
if ((*token)[0] == '/')
{
(*token)++;
if (!fixIndex(atoi((*token)), vnsize, &(vi.vn_idx)))
{
return false;
}
(*token) += strcspn((*token), "/ \t\r");
(*ret) = vi;
return true;
}
// i/j/k or i/j
if (!fixIndex(atoi((*token)), vtsize, &(vi.vt_idx)))
{
return false;
}
(*token) += strcspn((*token), "/ \t\r");
if ((*token)[0] != '/')
{
(*ret) = vi;
return true;
}
// i/j/k
(*token)++; // skip '/'
if (!fixIndex(atoi((*token)), vnsize, &(vi.vn_idx)))
{
return false;
}
(*token) += strcspn((*token), "/ \t\r");
(*ret) = vi;
return true;
}
static bool exportFaceGroupToShape(shape_t* shape, const std::vector<face_t>& face_group,
const material_t material, const std::string& name,
const std::vector<float>& v)
{
if (face_group.empty())
{
return false;
}
shape->name = name;
// Flattened version of vertex data
std::vector<float> positions;
std::vector<float> normals;
std::vector<float> texcoords;
std::map<vertex_index, unsigned int> vertexCache;
std::vector<unsigned int> indices;
// Flatten vertices and indices
for (size_t i = 0; i < faceGroup.size(); i++)
for (size_t i = 0; i < face_group.size(); i++)
{
const MyIndices& face = faceGroup[i];
vertex_index i0 = allIndices[face.m_offset];
vertex_index i1;
i1.vn_idx = -1;
i1.vt_idx = -1;
i1.v_idx = -1;
vertex_index i2 = allIndices[face.m_offset + 1];
size_t npolys = face.m_numIndices; //.size();
const face_t& face = face_group[i];
size_t npolys = face.size();
if (npolys < 3)
{
// Polygon -> triangle fan conversion
for (size_t k = 2; k < npolys; k++)
// Face must have 3+ vertices.
continue;
}
vertex_index_t i0 = face[0];
vertex_index_t i1(-1);
vertex_index_t i2 = face[1];
face_t remainingFace = face; // copy
size_t guess_vert = 0;
vertex_index_t ind[3];
// How many iterations can we do without decreasing the remaining
// vertices.
size_t remainingIterations = face.size();
size_t previousRemainingVertices = remainingFace.size();
while (remainingFace.size() > 3 && remainingIterations > 0)
{
npolys = remainingFace.size();
if (guess_vert >= npolys)
{
i1 = i2;
i2 = allIndices[face.m_offset + k];
guess_vert -= npolys;
}
unsigned int v0 = updateVertex(vertexCache, positions, normals, texcoords, in_positions, in_normals, in_texcoords, i0);
unsigned int v1 = updateVertex(vertexCache, positions, normals, texcoords, in_positions, in_normals, in_texcoords, i1);
unsigned int v2 = updateVertex(vertexCache, positions, normals, texcoords, in_positions, in_normals, in_texcoords, i2);
if (previousRemainingVertices != npolys)
{
// The number of remaining vertices decreased. Reset counters.
previousRemainingVertices = npolys;
remainingIterations = npolys;
}
else
{
// We didn't consume a vertex on previous iteration, reduce the
// available iterations.
remainingIterations--;
}
indices.push_back(v0);
indices.push_back(v1);
indices.push_back(v2);
for (size_t k = 0; k < 3; k++)
{
ind[k] = remainingFace[(guess_vert + k) % npolys];
size_t vi = size_t(ind[k].v_idx);
}
// this triangle is an ear
{
index_t idx0, idx1, idx2;
idx0.vertex_index = ind[0].v_idx;
idx0.normal_index = ind[0].vn_idx;
idx0.texcoord_index = ind[0].vt_idx;
idx1.vertex_index = ind[1].v_idx;
idx1.normal_index = ind[1].vn_idx;
idx1.texcoord_index = ind[1].vt_idx;
idx2.vertex_index = ind[2].v_idx;
idx2.normal_index = ind[2].vn_idx;
idx2.texcoord_index = ind[2].vt_idx;
shape->mesh.indices.push_back(idx0);
shape->mesh.indices.push_back(idx1);
shape->mesh.indices.push_back(idx2);
}
// remove v1 from the list
size_t removed_vert_index = (guess_vert + 1) % npolys;
while (removed_vert_index + 1 < npolys)
{
remainingFace[removed_vert_index] =
remainingFace[removed_vert_index + 1];
removed_vert_index += 1;
}
remainingFace.pop_back();
}
if (remainingFace.size() == 3)
{
i0 = remainingFace[0];
i1 = remainingFace[1];
i2 = remainingFace[2];
{
index_t idx0, idx1, idx2;
idx0.vertex_index = i0.v_idx;
idx0.normal_index = i0.vn_idx;
idx0.texcoord_index = i0.vt_idx;
idx1.vertex_index = i1.v_idx;
idx1.normal_index = i1.vn_idx;
idx1.texcoord_index = i1.vt_idx;
idx2.vertex_index = i2.v_idx;
idx2.normal_index = i2.vn_idx;
idx2.texcoord_index = i2.vt_idx;
shape->mesh.indices.push_back(idx0);
shape->mesh.indices.push_back(idx1);
shape->mesh.indices.push_back(idx2);
}
}
}
//
// Construct shape.
//
shape.name = name;
shape.mesh.positions.swap(positions);
shape.mesh.normals.swap(normals);
shape.mesh.texcoords.swap(texcoords);
shape.mesh.indices.swap(indices);
shape.material = material;
shape->material = material;
return true;
}
@@ -329,7 +332,6 @@ void InitMaterial(material_t& material)
material.ambient_texname = "";
material.diffuse_texname = "";
material.specular_texname = "";
material.normal_texname = "";
for (int i = 0; i < 3; i++)
{
material.ambient[i] = 0.f;
@@ -369,8 +371,8 @@ std::string LoadMtl(
return err.str();
}
#else
int fileHandle = fileIO->fileOpen(filepath.c_str(),"r");
if (fileHandle<0)
int fileHandle = fileIO->fileOpen(filepath.c_str(), "r");
if (fileHandle < 0)
{
err << "Cannot open file [" << filepath << "]" << std::endl;
return err.str();
@@ -396,7 +398,7 @@ std::string LoadMtl(
line = fileIO->readLine(fileHandle, tmpBuf, 1024);
if (line)
{
linebuf=line;
linebuf = line;
}
#endif
@@ -420,7 +422,7 @@ std::string LoadMtl(
// Skip leading space.
const char* token = linebuf.c_str();
token += strspn(token, " \t");
assert(token);
if (token[0] == '\0') continue; // empty line
@@ -574,12 +576,13 @@ std::string LoadMtl(
}
}
#ifndef USE_STREAM
while (line);
while (line)
;
#endif
// flush last material.
material_map.insert(std::pair<std::string, material_t>(material.name, material));
if (fileHandle>=0)
if (fileHandle >= 0)
{
fileIO->fileClose(fileHandle);
}
@@ -588,11 +591,16 @@ std::string LoadMtl(
std::string
LoadObj(
attrib_t& attrib,
std::vector<shape_t>& shapes,
const char* filename,
const char* mtl_basepath,
CommonFileIOInterface* fileIO)
{
attrib.vertices.clear();
attrib.normals.clear();
attrib.texcoords.clear();
shapes.clear();
std::string tmp = filename;
if (!mtl_basepath)
{
@@ -604,13 +612,6 @@ LoadObj(
mtl_basepath = tmp.c_str();
//fprintf(stderr, "MTL PATH '%s' orig '%s'\n", mtl_basepath, filename);
}
shapes.resize(0);
std::vector<vertex_index> allIndices;
allIndices.reserve(1024 * 1024);
MyIndices face;
std::stringstream err;
#ifdef USE_STREAM
std::ifstream ifs(filename);
@@ -620,8 +621,8 @@ LoadObj(
return err.str();
}
#else
int fileHandle = fileIO->fileOpen(filename,"r");
if (fileHandle<0)
int fileHandle = fileIO->fileOpen(filename, "r");
if (fileHandle < 0)
{
err << "Cannot open file [" << filename << "]" << std::endl;
return err.str();
@@ -629,16 +630,15 @@ LoadObj(
#endif
std::vector<float> v;
v.reserve(1024 * 1024);
std::vector<float> vn;
vn.reserve(1024 * 1024);
std::vector<float> vt;
vt.reserve(1024 * 1024);
//std::vector<std::vector<vertex_index> > faceGroup;
std::vector<MyIndices> faceGroup;
faceGroup.reserve(1024 * 1024);
std::string name;
int greatest_v_idx = -1;
int greatest_vn_idx = -1;
int greatest_vt_idx = -1;
std::vector<face_t> faceGroup;
// material
std::map<std::string, material_t> material_map;
material_t material;
@@ -664,10 +664,9 @@ LoadObj(
line = fileIO->readLine(fileHandle, tmpBuf, 1024);
if (line)
{
linebuf=line;
linebuf = line;
}
#endif
// Trim newline '\r\n' or '\r'
if (linebuf.size() > 0)
{
@@ -734,23 +733,34 @@ LoadObj(
token += 2;
token += strspn(token, " \t");
face.m_offset = allIndices.size();
face.m_numIndices = 0;
face_t face;
face.reserve(3);
while (!isNewLine(token[0]))
{
vertex_index vi = parseTriple(token, v.size() / 3, vn.size() / 3, vt.size() / 2);
allIndices.push_back(vi);
face.m_numIndices++;
int n = strspn(token, " \t\r");
vertex_index_t vi;
if (!parseTriple(&token, static_cast<int>(v.size() / 3),
static_cast<int>(vn.size() / 3),
static_cast<int>(vt.size() / 2), &vi))
{
err << "Failed parse `f' line(e.g. zero value for face index.";
return err.str();
}
greatest_v_idx = greatest_v_idx > vi.v_idx ? greatest_v_idx : vi.v_idx;
greatest_vn_idx =
greatest_vn_idx > vi.vn_idx ? greatest_vn_idx : vi.vn_idx;
greatest_vt_idx =
greatest_vt_idx > vi.vt_idx ? greatest_vt_idx : vi.vt_idx;
face.push_back(vi);
size_t n = strspn(token, " \t\r");
token += n;
}
faceGroup.push_back(face);
continue;
}
// use mtl
if ((0 == strncmp(token, "usemtl", 6)) && isSpace((token[6])))
{
@@ -777,10 +787,10 @@ LoadObj(
token += 7;
sscanf(token, "%s", namebuf);
std::string err_mtl = LoadMtl(material_map, namebuf, mtl_basepath,fileIO);
std::string err_mtl = LoadMtl(material_map, namebuf, mtl_basepath, fileIO);
if (!err_mtl.empty())
{
//faceGroup.resize(0); // for safety
//face_group.resize(0); // for safety
//return err_mtl;
}
continue;
@@ -791,7 +801,7 @@ LoadObj(
{
// flush previous face group.
shape_t shape;
bool ret = exportFaceGroupToShape(shape, v, vn, vt, faceGroup, material, name, allIndices);
bool ret = exportFaceGroupToShape(&shape, faceGroup, material, name, v);
if (ret)
{
shapes.push_back(shape);
@@ -827,7 +837,7 @@ LoadObj(
{
// flush previous face group.
shape_t shape;
bool ret = exportFaceGroupToShape(shape, v, vn, vt, faceGroup, material, name, allIndices);
bool ret = exportFaceGroupToShape(&shape, faceGroup, material, name, v);
if (ret)
{
shapes.push_back(shape);
@@ -847,18 +857,23 @@ LoadObj(
// Ignore unknown command.
}
#ifndef USE_STREAM
while (line);
while (line)
;
#endif
shape_t shape;
bool ret = exportFaceGroupToShape(shape, v, vn, vt, faceGroup, material, name, allIndices);
bool ret = exportFaceGroupToShape(&shape, faceGroup, material, name, v);
if (ret)
{
shapes.push_back(shape);
}
faceGroup.resize(0); // for safety
if (fileHandle>=0)
attrib.vertices.swap(v);
attrib.normals.swap(vn);
attrib.texcoords.swap(vt);
if (fileHandle >= 0)
{
fileIO->fileClose(fileHandle);
}

View File

@@ -14,6 +14,17 @@ struct CommonFileIOInterface;
namespace tinyobj
{
struct vertex_index_t
{
int v_idx, vt_idx, vn_idx;
vertex_index_t() : v_idx(-1), vt_idx(-1), vn_idx(-1) {}
explicit vertex_index_t(int idx) : v_idx(idx), vt_idx(idx), vn_idx(idx) {}
vertex_index_t(int vidx, int vtidx, int vnidx)
: v_idx(vidx), vt_idx(vtidx), vn_idx(vnidx) {}
};
typedef std::vector<vertex_index_t> face_t;
typedef struct
{
std::string name;
@@ -24,21 +35,27 @@ typedef struct
float transmittance[3];
float emission[3];
float shininess;
float transparency;
float transparency; // 1 == opaque; 0 == fully transparent
std::string ambient_texname;
std::string diffuse_texname;
std::string specular_texname;
std::string ambient_texname; // map_Ka
std::string diffuse_texname; // map_Kd
std::string specular_texname; // map_Ks
std::string normal_texname;
std::map<std::string, std::string> unknown_parameter;
} material_t;
// Index struct to support different indices for vtx/normal/texcoord.
// -1 means not used.
typedef struct
{
std::vector<float> positions;
std::vector<float> normals;
std::vector<float> texcoords;
std::vector<unsigned int> indices;
int vertex_index;
int normal_index;
int texcoord_index;
} index_t;
typedef struct
{
std::vector<index_t> indices;
} mesh_t;
typedef struct
@@ -48,6 +65,14 @@ typedef struct
mesh_t mesh;
} shape_t;
// Vertex attributes
struct attrib_t
{
std::vector<float> vertices; // 'v'(xyz)
std::vector<float> normals; // 'vn'
std::vector<float> texcoords; // 'vt'(uv)
attrib_t() {}
};
/// Loads .obj from a file.
/// 'shapes' will be filled with parsed shape data
/// The function returns error string.
@@ -55,12 +80,14 @@ typedef struct
/// 'mtl_basepath' is optional, and used for base path for .mtl file.
#ifdef USE_STREAM
std::string LoadObj(
attrib_t& attrib,
std::vector<shape_t>& shapes, // [output]
const char* filename,
const char* mtl_basepath = NULL);
#else
std::string
LoadObj(
attrib_t& attrib,
std::vector<shape_t>& shapes,
const char* filename,
const char* mtl_basepath,