clean up initialization and the rigid flag

This commit is contained in:
jingyuc 2022-02-20 02:27:18 -08:00
parent ca334946a7
commit 41ce1cca24
15 changed files with 177 additions and 133 deletions

View File

@ -216,7 +216,14 @@ void ConservationTest::initPhysics()
// create volumetric reduced deformable body
{
btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedBeam(getDeformableDynamicsWorld()->getWorldInfo(), num_modes);
std::string file_path("../../../data/reduced_beam/");
std::string vtk_file("beam_mesh_origin.vtk");
btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedDeformableObject(
getDeformableDynamicsWorld()->getWorldInfo(),
file_path,
vtk_file,
num_modes,
false);
getDeformableDynamicsWorld()->addSoftBody(rsb);
rsb->getCollisionShape()->setMargin(0.1);

View File

@ -32,7 +32,7 @@
static btScalar damping_alpha = 0.0;
static btScalar damping_beta = 0.0001;
static btScalar COLLIDING_VELOCITY = 0;
static int num_modes = 20;
static int num_modes = 40;
class FreeFall : public CommonDeformableBodyBase
{
@ -55,7 +55,7 @@ public:
void resetCamera()
{
float dist = 6;
float dist = 8;
float pitch = -10;
float yaw = 90;
float targetPos[3] = {0, 2, 0};
@ -81,12 +81,19 @@ public:
// startTransform.setRotation(btQuaternion(btVector3(1, 0, 1), SIMD_PI / 4.0));
btRigidBody* rb1 = createRigidBody(mass, startTransform, shape);
rb1->setActivationState(DISABLE_DEACTIVATION);
rb1->setLinearVelocity(btVector3(0, -4, 0));
rb1->setLinearVelocity(btVector3(0, 0, 0));
}
void createReducedDeformableObject(const btVector3& origin, const btQuaternion& rotation)
{
btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedCube(getDeformableDynamicsWorld()->getWorldInfo(), num_modes);
std::string file_path("../../../data/reduced_cube/");
std::string vtk_file("cube_mesh.vtk");
btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedDeformableObject(
getDeformableDynamicsWorld()->getWorldInfo(),
file_path,
vtk_file,
num_modes,
false);
getDeformableDynamicsWorld()->addSoftBody(rsb);
rsb->getCollisionShape()->setMargin(0.01);
@ -100,7 +107,7 @@ public:
init_transform.setRotation(rotation);
rsb->transformTo(init_transform);
rsb->setStiffnessScale(5);
rsb->setStiffnessScale(25);
rsb->setDamping(damping_alpha, damping_beta);
// rsb->scale(btVector3(0.5, 0.5, 0.5));
@ -168,18 +175,18 @@ void FreeFall::initPhysics()
m_solver = sol;
m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, reducedSoftBodySolver);
btVector3 gravity = btVector3(0, 0, 0);
btVector3 gravity = btVector3(0, -9.8, 0);
m_dynamicsWorld->setGravity(gravity);
m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld);
// m_dynamicsWorld->getSolverInfo().m_solverMode |= SOLVER_RANDMIZE_ORDER;
// 2 reduced deformable cubes
createReducedDeformableObject(btVector3(0, 1, -2), btQuaternion(0, 0, 0));
createReducedDeformableObject(btVector3(0, 1, 2), btQuaternion(0, 0, 0));
createReducedDeformableObject(btVector3(0, 4, -2), btQuaternion(0, 0, 0));
createReducedDeformableObject(btVector3(0, 4, 2), btQuaternion(0, 0, 0));
// 2 rigid cubes
Ctor_RbUpStack(btVector3(0, 3, -2));
Ctor_RbUpStack(btVector3(0, 3, 2));
Ctor_RbUpStack(btVector3(0, 10, -2));
Ctor_RbUpStack(btVector3(0, 10, 2));
// create a static rigid box as the ground
{

View File

@ -187,7 +187,14 @@ void FrictionSlope::initPhysics()
// create volumetric reduced deformable body
{
btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedBeam(getDeformableDynamicsWorld()->getWorldInfo(), num_modes);
std::string file_path("../../../data/reduced_beam/");
std::string vtk_file("beam_mesh_origin.vtk");
btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedDeformableObject(
getDeformableDynamicsWorld()->getWorldInfo(),
file_path,
vtk_file,
num_modes,
false);
getDeformableDynamicsWorld()->addSoftBody(rsb);
rsb->getCollisionShape()->setMargin(0.01);

View File

@ -135,7 +135,14 @@ void ModeVisualizer::initPhysics()
// create volumetric soft body
{
btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedCube(getDeformableDynamicsWorld()->getWorldInfo(), num_modes);
std::string file_path("../../../data/reduced_cube/");
std::string vtk_file("cube_mesh.vtk");
btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedDeformableObject(
getDeformableDynamicsWorld()->getWorldInfo(),
file_path,
vtk_file,
num_modes,
false);
getDeformableDynamicsWorld()->addSoftBody(rsb);
rsb->getCollisionShape()->setMargin(0.1);

View File

@ -87,74 +87,81 @@ public:
{
if (run_reduced)
{
btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedTorus(getDeformableDynamicsWorld()->getWorldInfo(), num_modes);
{
std::string file_path("../../../data/reduced_torus/");
std::string vtk_file("torus_mesh.vtk");
btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedDeformableObject(
getDeformableDynamicsWorld()->getWorldInfo(),
file_path,
vtk_file,
num_modes,
false);
getDeformableDynamicsWorld()->addSoftBody(rsb);
rsb->getCollisionShape()->setMargin(0.01);
// rsb->scale(btVector3(1, 1, 0.5));
getDeformableDynamicsWorld()->addSoftBody(rsb);
rsb->getCollisionShape()->setMargin(0.01);
// rsb->scale(btVector3(1, 1, 0.5));
rsb->setTotalMass(10);
rsb->setTotalMass(10);
btTransform init_transform;
init_transform.setIdentity();
init_transform.setOrigin(origin);
init_transform.setRotation(rotation);
rsb->transformTo(init_transform);
btTransform init_transform;
init_transform.setIdentity();
init_transform.setOrigin(origin);
init_transform.setRotation(rotation);
rsb->transformTo(init_transform);
rsb->setStiffnessScale(5);
rsb->setDamping(damping_alpha, damping_beta);
// rsb->scale(btVector3(0.5, 0.5, 0.5));
rsb->setStiffnessScale(5);
rsb->setDamping(damping_alpha, damping_beta);
// rsb->scale(btVector3(0.5, 0.5, 0.5));
rsb->m_cfg.kKHR = 1; // collision hardness with kinematic objects
rsb->m_cfg.kCHR = 1; // collision hardness with rigid body
rsb->m_cfg.kDF = 0;
rsb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD;
rsb->m_cfg.collisions |= btSoftBody::fCollision::SDF_RDN;
rsb->m_sleepingThreshold = 0;
btSoftBodyHelpers::generateBoundaryFaces(rsb);
rsb->m_cfg.kKHR = 1; // collision hardness with kinematic objects
rsb->m_cfg.kCHR = 1; // collision hardness with rigid body
rsb->m_cfg.kDF = 0;
rsb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD;
rsb->m_cfg.collisions |= btSoftBody::fCollision::SDF_RDN;
rsb->m_sleepingThreshold = 0;
btSoftBodyHelpers::generateBoundaryFaces(rsb);
std::cout << "Running reduced deformable\n";
}
else // create full deformable cube
{
std::string filepath("../../../data/reduced_torus/");
std::string filename = filepath + "torus_mesh.vtk";
btSoftBody* psb = btSoftBodyHelpers::CreateFromVtkFile(getDeformableDynamicsWorld()->getWorldInfo(), filename.c_str());
btTransform init_transform;
init_transform.setIdentity();
init_transform.setOrigin(origin);
init_transform.setRotation(rotation);
psb->transform(init_transform);
psb->getCollisionShape()->setMargin(0.015);
psb->setTotalMass(10);
psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects
psb->m_cfg.kCHR = 1; // collision hardness with rigid body
psb->m_cfg.kDF = .5;
psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD;
psb->m_cfg.collisions |= btSoftBody::fCollision::SDF_RDN;
getDeformableDynamicsWorld()->addSoftBody(psb);
btSoftBodyHelpers::generateBoundaryFaces(psb);
btDeformableGravityForce* gravity_force = new btDeformableGravityForce(m_gravity);
getDeformableDynamicsWorld()->addForce(psb, gravity_force);
m_forces.push_back(gravity_force);
btScalar E = 10000;
btScalar nu = 0.3;
btScalar lambda = E * nu / ((1 + nu) * (1 - 2 * nu));
btScalar mu = E / (2 * (1 + nu));
btDeformableNeoHookeanForce* neohookean = new btDeformableNeoHookeanForce(lambda, mu, 0.01);
// neohookean->setPoissonRatio(0.3);
// neohookean->setYoungsModulus(25);
neohookean->setDamping(0.01);
psb->m_cfg.drag = 0.001;
getDeformableDynamicsWorld()->addForce(psb, neohookean);
m_forces.push_back(neohookean);
std::cout << "Running reduced deformable\n";
}
else // create full deformable cube
{
std::string filepath("../../../data/reduced_torus/");
std::string filename = filepath + "torus_mesh.vtk";
btSoftBody* psb = btSoftBodyHelpers::CreateFromVtkFile(getDeformableDynamicsWorld()->getWorldInfo(), filename.c_str());
btTransform init_transform;
init_transform.setIdentity();
init_transform.setOrigin(origin);
init_transform.setRotation(rotation);
psb->transform(init_transform);
psb->getCollisionShape()->setMargin(0.015);
psb->setTotalMass(10);
psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects
psb->m_cfg.kCHR = 1; // collision hardness with rigid body
psb->m_cfg.kDF = .5;
psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD;
psb->m_cfg.collisions |= btSoftBody::fCollision::SDF_RDN;
getDeformableDynamicsWorld()->addSoftBody(psb);
btSoftBodyHelpers::generateBoundaryFaces(psb);
btDeformableGravityForce* gravity_force = new btDeformableGravityForce(m_gravity);
getDeformableDynamicsWorld()->addForce(psb, gravity_force);
m_forces.push_back(gravity_force);
btScalar E = 10000;
btScalar nu = 0.3;
btScalar lambda = E * nu / ((1 + nu) * (1 - 2 * nu));
btScalar mu = E / (2 * (1 + nu));
btDeformableNeoHookeanForce* neohookean = new btDeformableNeoHookeanForce(lambda, mu, 0.01);
// neohookean->setPoissonRatio(0.3);
// neohookean->setYoungsModulus(25);
neohookean->setDamping(0.01);
psb->m_cfg.drag = 0.001;
getDeformableDynamicsWorld()->addForce(psb, neohookean);
m_forces.push_back(neohookean);
std::cout << "Running full deformable\n";
}
std::cout << "Running full deformable\n";
}
// btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedTorus(getDeformableDynamicsWorld()->getWorldInfo(), num_modes);

View File

@ -204,8 +204,15 @@ void ReducedCollide::initPhysics()
// create volumetric reduced deformable body
{
btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedCube(getDeformableDynamicsWorld()->getWorldInfo(), num_modes);
std::string file_path("../../../data/reduced_cube/");
std::string vtk_file("cube_mesh.vtk");
btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedDeformableObject(
getDeformableDynamicsWorld()->getWorldInfo(),
file_path,
vtk_file,
num_modes,
false);
getDeformableDynamicsWorld()->addSoftBody(rsb);
rsb->getCollisionShape()->setMargin(0.1);
// rsb->scale(btVector3(0.5, 0.5, 0.5));

View File

@ -278,8 +278,15 @@ void ReducedGrasp::initPhysics()
// create volumetric reduced deformable body
{
btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedCube(getDeformableDynamicsWorld()->getWorldInfo(), num_modes);
std::string file_path("../../../data/reduced_cube/");
std::string vtk_file("cube_mesh.vtk");
btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedDeformableObject(
getDeformableDynamicsWorld()->getWorldInfo(),
file_path,
vtk_file,
num_modes,
false);
getDeformableDynamicsWorld()->addSoftBody(rsb);
rsb->getCollisionShape()->setMargin(0.015);

View File

@ -317,8 +317,14 @@ void ReducedMotorGrasp::initPhysics()
// create volumetric reduced deformable body
{
btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedCube(getDeformableDynamicsWorld()->getWorldInfo(), num_modes);
std::string file_path("../../../data/reduced_cube/");
std::string vtk_file("cube_mesh.vtk");
btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedDeformableObject(
getDeformableDynamicsWorld()->getWorldInfo(),
file_path,
vtk_file,
num_modes,
false);
getDeformableDynamicsWorld()->addSoftBody(rsb);
rsb->getCollisionShape()->setMargin(0.001);

View File

@ -141,7 +141,14 @@ void Springboard::initPhysics()
// create volumetric reduced deformable body
{
btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedBeam(getDeformableDynamicsWorld()->getWorldInfo(), num_modes);
std::string file_path("../../../data/reduced_beam/");
std::string vtk_file("beam_mesh_origin.vtk");
btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createReducedDeformableObject(
getDeformableDynamicsWorld()->getWorldInfo(),
file_path,
vtk_file,
num_modes,
false);
getDeformableDynamicsWorld()->addSoftBody(rsb);
rsb->getCollisionShape()->setMargin(0.1);

View File

@ -6,10 +6,8 @@
#include <fstream>
btReducedDeformableBody::btReducedDeformableBody(btSoftBodyWorldInfo* worldInfo, int node_count, const btVector3* x, const btScalar* m)
: btSoftBody(worldInfo, node_count, x, m)
: btSoftBody(worldInfo, node_count, x, m), m_rigidOnly(false)
{
m_rigidOnly = true; //! only use rigid frame to debug
// reduced deformable
m_reducedModel = true;
m_nReduced = 0;
@ -781,4 +779,14 @@ const btVector3& btReducedDeformableBody::getLinearVelocity() const
const btVector3& btReducedDeformableBody::getAngularVelocity() const
{
return m_angularVelocity;
}
void btReducedDeformableBody::disableReducedModes(const bool rigid_only)
{
m_rigidOnly = rigid_only;
}
bool btReducedDeformableBody::isReducedModesOFF() const
{
return m_rigidOnly;
}

View File

@ -20,6 +20,9 @@ class btReducedDeformableBody : public btSoftBody
typedef btAlignedObjectArray<btAlignedObjectArray<btScalar> > tDenseMatrix;
private:
// flag to turn off the reduced modes
bool m_rigidOnly;
// Flags for transform. Once transform is applied, users cannot scale the mesh or change its total mass.
bool m_transform_lock;
@ -66,9 +69,6 @@ class btReducedDeformableBody : public btSoftBody
btScalar m_dampingBeta;
public:
bool m_rigidOnly;
//
// Fields
//
@ -126,6 +126,8 @@ class btReducedDeformableBody : public btSoftBody
void setDamping(const btScalar alpha, const btScalar beta);
void disableReducedModes(const bool rigid_only);
virtual void setTotalMass(btScalar mass, bool fromfaces = false);
//
@ -228,6 +230,7 @@ class btReducedDeformableBody : public btSoftBody
//
// accessors
//
bool isReducedModesOFF() const;
btScalar getTotalMass() const;
btTransform& getRigidTransform();
const btVector3& getLinearVelocity() const;

View File

@ -4,43 +4,18 @@
#include <string>
#include <sstream>
btReducedDeformableBody* btReducedDeformableBodyHelpers::createReducedBeam(btSoftBodyWorldInfo& worldInfo, const int num_modes)
{
std::string filepath("../../../data/reduced_beam/");
// std::string filename = filepath + "beam_mesh.vtk";
std::string filename = filepath + "beam_mesh_origin.vtk";
btReducedDeformableBody* btReducedDeformableBodyHelpers::createReducedDeformableObject(btSoftBodyWorldInfo& worldInfo, const std::string& file_path, const std::string& vtk_file, const int num_modes, bool rigid_only) {
std::string filename = file_path + vtk_file;
btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createFromVtkFile(worldInfo, filename.c_str());
rsb->setReducedModes(num_modes, rsb->m_nodes.size());
btReducedDeformableBodyHelpers::readReducedDeformableInfoFromFiles(rsb, filepath.c_str());
btReducedDeformableBodyHelpers::readReducedDeformableInfoFromFiles(rsb, file_path.c_str());
rsb->disableReducedModes(rigid_only);
return rsb;
}
btReducedDeformableBody* btReducedDeformableBodyHelpers::createReducedCube(btSoftBodyWorldInfo& worldInfo, const int num_modes)
{
std::string filepath("../../../data/reduced_cube/");
std::string filename = filepath + "cube_mesh.vtk";
btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createFromVtkFile(worldInfo, filename.c_str());
rsb->setReducedModes(num_modes, rsb->m_nodes.size());
btReducedDeformableBodyHelpers::readReducedDeformableInfoFromFiles(rsb, filepath.c_str());
return rsb;
}
btReducedDeformableBody* btReducedDeformableBodyHelpers::createReducedTorus(btSoftBodyWorldInfo& worldInfo, const int num_modes)
{
std::string filepath("../../../data/reduced_torus/");
std::string filename = filepath + "torus_mesh.vtk";
btReducedDeformableBody* rsb = btReducedDeformableBodyHelpers::createFromVtkFile(worldInfo, filename.c_str());
rsb->setReducedModes(num_modes, rsb->m_nodes.size());
btReducedDeformableBodyHelpers::readReducedDeformableInfoFromFiles(rsb, filepath.c_str());
return rsb;
}
btReducedDeformableBody* btReducedDeformableBodyHelpers::createFromVtkFile(btSoftBodyWorldInfo& worldInfo, const char* vtk_file)
{
std::ifstream fs;

View File

@ -2,16 +2,12 @@
#define BT_REDUCED_SOFT_BODY_HELPERS_H
#include "btReducedDeformableBody.h"
#include <string>
struct btReducedDeformableBodyHelpers
{
// create a beam
static btReducedDeformableBody* createReducedBeam(btSoftBodyWorldInfo& worldInfo, const int num_modes);
// create a cube
static btReducedDeformableBody* createReducedCube(btSoftBodyWorldInfo& worldInfo, const int num_modes);
// create a torus
static btReducedDeformableBody* createReducedTorus(btSoftBodyWorldInfo& worldInfo, const int num_modes);
// create a reduced deformable object
static btReducedDeformableBody* createReducedDeformableObject(btSoftBodyWorldInfo& worldInfo, const std::string& file_path, const std::string& vtk_file, const int num_modes, bool rigid_only);
// read in geometry info from Vtk file
static btReducedDeformableBody* createFromVtkFile(btSoftBodyWorldInfo& worldInfo, const char* vtk_file);
// read in all reduced files

View File

@ -145,7 +145,7 @@ void btReducedDeformableBodySolver::applyExplicitForce(btScalar solverdt)
// apply gravity to the rigid frame, get m_linearVelocity at time^*
rsb->applyRigidGravity(m_gravity, solverdt);
if (!rsb->m_rigidOnly)
if (!rsb->isReducedModesOFF())
{
// add internal force (elastic force & damping force)
rsb->applyReducedElasticForce(rsb->m_reducedDofsBuffer);
@ -169,7 +169,7 @@ void btReducedDeformableBodySolver::applyTransforms(btScalar timeStep)
// rigid motion
rsb->proceedToTransform(timeStep, true);
if (!rsb->m_rigidOnly)
if (!rsb->isReducedModesOFF())
{
// update reduced dofs for time^n+1
rsb->updateReducedDofs(timeStep);
@ -233,8 +233,8 @@ void btReducedDeformableBodySolver::setConstraints(const btContactSolverInfo& in
m_nodeRigidConstraints[i].push_back(constraint);
rsb->m_contactNodesList.push_back(contact.m_node->index - rsb->m_nodeIndexOffset);
}
std::cout << "contact node list size: " << rsb->m_contactNodesList.size() << "\n";
std::cout << "#contact nodes: " << m_nodeRigidConstraints[i].size() << "\n";
// std::cout << "contact node list size: " << rsb->m_contactNodesList.size() << "\n";
// std::cout << "#contact nodes: " << m_nodeRigidConstraints[i].size() << "\n";
}
}
@ -292,7 +292,7 @@ btScalar btReducedDeformableBodySolver::solveContactConstraints(btCollisionObjec
// handle contact constraint
// node vs rigid contact
std::cout << "!!#contact_nodes: " << m_nodeRigidConstraints[i].size() << '\n';
// std::cout << "!!#contact_nodes: " << m_nodeRigidConstraints[i].size() << '\n';
for (int k = 0; k < m_nodeRigidConstraints[i].size(); ++k)
{
btReducedDeformableNodeRigidContactConstraint& constraint = m_nodeRigidConstraints[i][m_orderContactConstraintPool[k]];

View File

@ -43,8 +43,8 @@ btScalar btDeformableMultiBodyConstraintSolver::solveDeformableGroupIterations(b
writeToSolverBody(bodies, numBodies, infoGlobal);
std::cout << "------------Iteration " << iteration << "------------\n";
std::cout << "m_leastSquaresResidual: " << m_leastSquaresResidual << "\n";
// std::cout << "------------Iteration " << iteration << "------------\n";
// std::cout << "m_leastSquaresResidual: " << m_leastSquaresResidual << "\n";
if (m_leastSquaresResidual <= infoGlobal.m_leastSquaresResidualThreshold || (iteration >= (maxIterations - 1)))
{
@ -62,7 +62,7 @@ btScalar btDeformableMultiBodyConstraintSolver::solveDeformableGroupIterations(b
m_analyticsData.m_remainingLeastSquaresResidual = m_leastSquaresResidual;
m_deformableSolver->deformableBodyInternalWriteBack();
std::cout << "[===================Next Step===================]\n";
// std::cout << "[===================Next Step===================]\n";
break;
}
}
@ -155,7 +155,7 @@ void btDeformableMultiBodyConstraintSolver::pairDeformableAndSolverBody(btCollis
const btRigidBody* body = btRigidBody::upcast(bodies[bodyId]);
if (body && body->getInvMass())
{
std::cout << "Node: " << constraint.m_node->index << ", body: " << bodyId << "\n";
// std::cout << "Node: " << constraint.m_node->index << ", body: " << bodyId << "\n";
btSolverBody& solverBody = m_tmpSolverBodyPool[bodyId];
constraint.setSolverBody(bodyId, solverBody);
}