I have created a sleeved joint. If you want, I have reproduced source code to be integrated into the SoftDemo.cpp file. A video of screen-captures is posted at: http://youtu.be/LiYYqO2BxyQ
I also have a question, request for improvement. When the joint includes a "ball", body3 in the code below, at large joint angles, the cloth passes through the ball. I think it is similar to some cloth problems that other people were reporting in this forum. If you can fix it, please do so. I have been trying to fix it with smaller timesteps, collision margins, and other things suggested without much success. This also happens if the joint is flexed too fast.
Thanks, Prakash.
SoftDemo.cpp
Code: Select all
static btScalar SleeveTriMesh_GetX(const int m, const int M, const btVector3& origin, const btScalar r)
{
return origin.x() + r*cos(2*M_PI/(M + 0.0)*m);
}
static btScalar SleeveTriMesh_GetZ(const int m, const int M, const btVector3& origin, const btScalar r)
{
return origin.z() + r*sin(2*M_PI/(M + 0.0)*m);
}
static btScalar SleeveTriMesh_GetY(const int n, const int N, const btVector3& origin, const btScalar h)
{
return origin.y() + h*n/(N - 1.0);
}
static void Init_SleevedJoint_GetSleeveTriMesh(btScalar* vertices,
int* triangles,
const int M, const int N, const btVector3& origin, const btScalar radius, const btScalar height)
{
for(int n = 0; n < N-1; n++)
for(int m = 0; m < M; m++)
{
int p = n*M + m;
vertices[p*3 + 0] = SleeveTriMesh_GetX(m, M, origin, radius);
vertices[p*3 + 1] = SleeveTriMesh_GetY(n, N, origin, height);
vertices[p*3 + 2] = SleeveTriMesh_GetZ(m, M, origin, radius);
triangles[6*p + 0] = p;
triangles[6*p + 1] = p + M;
triangles[6*p + 2] = (m == M - 1)?p - M + 1:p + 1;
triangles[6*p + 3] = triangles[6*p + 2];
triangles[6*p + 4] = p + M;
triangles[6*p + 5] = triangles[6*p + 2] + M;
}
for(int m = 0; m < M; m++)
{
int n = N - 1;
int p = n*M + m;
vertices[p*3 + 0] = SleeveTriMesh_GetX(m, M, origin, radius);
vertices[p*3 + 1] = SleeveTriMesh_GetY(n, N, origin, height);
vertices[p*3 + 2] = SleeveTriMesh_GetZ(m, M, origin, radius);
}
}
//
// Joint with sleeve.
//
static void Init_SleevedJoint(SoftDemo* pdemo)
{
const int COLLISION_MARGIN = 0.001;
const btScalar Z_LOCATION = 2.0;
const int M_PATCH = 30, N_PATCH = 30;
btScalar vertices[M_PATCH*N_PATCH*3];
const int ntriangles = M_PATCH*(N_PATCH - 1)*2;
int triangles[ntriangles*3];
Init_SleevedJoint_GetSleeveTriMesh(vertices, triangles,
M_PATCH, N_PATCH, btVector3(0, 1.5, Z_LOCATION), 2.1, 19);
//#define SLEEVE_DEBUG 1
#ifdef SLEEVE_DEBUG
for(int nv = 0; nv < M_PATCH*N_PATCH*3; nv++)
printf("vertices(%d) = %g\n", nv, vertices[nv]);
#endif
//
btTransform startTransform;
startTransform.setIdentity();
startTransform.setOrigin(btVector3(0, 4, Z_LOCATION));
btRigidBody* body1 = pdemo->localCreateRigidBody(50,startTransform,new btCapsuleShape(2,6));
body1->getCollisionShape()->setMargin(COLLISION_MARGIN);
body1->setRestitution(1.0);
body1->setDamping(0.9, 0.9);
body1->setCcdMotionThreshold(0.001);
startTransform.setIdentity();
startTransform.setOrigin(btVector3(0, 10.6, Z_LOCATION));
btRigidBody* body3 = pdemo->localCreateRigidBody(00,startTransform,new btSphereShape(1.5));
body3->getCollisionShape()->setMargin(COLLISION_MARGIN);
body3->setRestitution(1.0);
body3->setCcdMotionThreshold(0.001);
startTransform.setIdentity();
startTransform.setOrigin(btVector3(0, 17.2, Z_LOCATION));
btRigidBody* body2 = pdemo->localCreateRigidBody(00,startTransform,new btCapsuleShape(2,6));
body2->getCollisionShape()->setMargin(COLLISION_MARGIN);
btHingeConstraint *hingeC =
new btHingeConstraint(*body1,
btVector3(0, 5.5, 0),
btVector3(0, 0, 1)
);
hingeC->setLimit(btScalar(-M_PI_4), btScalar(M_PI_4));
pdemo->getDynamicsWorld()->addConstraint(hingeC, false);
btSoftBody* psb = btSoftBodyHelpers::CreateFromTriMesh( pdemo->m_softBodyWorldInfo,
vertices, triangles, ntriangles, false);
psb->getCollisionShape()->setMargin(COLLISION_MARGIN);
btSoftBody::Material* pm=psb->appendMaterial();
pm->m_kLST = 0.1;
//pm->m_flags -= btSoftBody::fMaterial::DebugDraw;
psb->generateBendingConstraints(3,pm);
psb->setTotalMass(10);
//psb->setFriction(500.0);
psb->m_cfg.kDF = 0.5;
psb->m_cfg.kDP = 0.2;
psb->m_cfg.kKHR = 1.0;
psb->m_cfg.kPR = 0.5;
//psb->m_cfg.piterations = 1;
psb->m_cfg.timescale = 0.1;
psb->setContactProcessingThreshold(0);
psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RS +
btSoftBody::fCollision::CL_SS +
btSoftBody::fCollision::CL_SELF;
//psb->generateClusters(64);
psb->setPose(true, false);
pdemo->getSoftDynamicsWorld()->addSoftBody(psb);
for (int m = 0; m < M_PATCH; m++) {
psb->appendAnchor(m, body1, false, 1.0);
psb->appendAnchor(M_PATCH*N_PATCH - m - 1, body2, false, 1.0);
}
pdemo->getDynamicsWorld()->getSolverInfo().m_splitImpulse = true;
pdemo->m_cutting=true;
}
Code: Select all
/* Init */
void (*demofncs[])(SoftDemo*)=
{
Init_Cloth,
Init_Pressure,
Init_Volume,
Init_Ropes,
Init_RopeAttach,
Init_ClothAttach,
Init_Sticks,
Init_Collide,
Init_Collide2,
Init_Collide3,
Init_Impact,
Init_Aero,
Init_Aero2,
Init_Friction,
Init_Torus,
Init_TorusMatch,
Init_Bunny,
Init_BunnyMatch,
Init_Cutting1,
Init_ClusterDeform,
Init_ClusterCollide1,
Init_ClusterCollide2,
Init_ClusterSocket,
Init_ClusterHinge,
Init_ClusterCombine,
Init_ClusterCar,
Init_ClusterRobot,
Init_ClusterStackSoft,
Init_ClusterStackMixed,
Init_TetraCube,
Init_TetraBunny,
Init_SleevedJoint
};
Code: Select all
MACRO_SOFT_DEMO(30)//Init_SleevedJointDemo