code clean up + Zlib copyright header
This commit is contained in:
@@ -1,8 +1,15 @@
|
||||
// btCGProjection.h
|
||||
// BulletSoftBody
|
||||
//
|
||||
// Created by Xuchen Han on 7/4/19.
|
||||
//
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2016 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 BT_CG_PROJECTION_H
|
||||
#define BT_CG_PROJECTION_H
|
||||
@@ -20,7 +27,6 @@ struct DeformableContactConstraint
|
||||
btAlignedObjectArray<btScalar> m_value;
|
||||
// the magnitude of the total impulse the node applied to the rb in the normal direction in the cg solve
|
||||
btAlignedObjectArray<btScalar> m_accumulated_normal_impulse;
|
||||
btSoftBody::Node* node;
|
||||
|
||||
DeformableContactConstraint(const btSoftBody::RContact& rcontact)
|
||||
{
|
||||
@@ -74,7 +80,6 @@ struct DeformableFrictionConstraint
|
||||
|
||||
// the total impulse the node applied to the rb in the tangential direction in the cg solve
|
||||
btAlignedObjectArray<btVector3> m_accumulated_tangent_impulse;
|
||||
btSoftBody::Node* node;
|
||||
|
||||
DeformableFrictionConstraint()
|
||||
{
|
||||
|
||||
@@ -1,9 +1,15 @@
|
||||
//
|
||||
// btConjugateGradient.h
|
||||
// BulletSoftBody
|
||||
//
|
||||
// Created by Xuchen Han on 7/1/19.
|
||||
//
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2016 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 BT_CONJUGATE_GRADIENT_H
|
||||
#define BT_CONJUGATE_GRADIENT_H
|
||||
@@ -12,7 +18,7 @@
|
||||
#include <LinearMath/btAlignedObjectArray.h>
|
||||
#include <LinearMath/btVector3.h>
|
||||
|
||||
template <class TM>
|
||||
template <class MatrixX>
|
||||
class btConjugateGradient
|
||||
{
|
||||
// using TVStack = btAlignedObjectArray<btVector3>;
|
||||
@@ -29,7 +35,7 @@ public:
|
||||
virtual ~btConjugateGradient(){}
|
||||
|
||||
// return the number of iterations taken
|
||||
int solve(TM& A, TVStack& x, const TVStack& b, btScalar tolerance)
|
||||
int solve(MatrixX& A, TVStack& x, const TVStack& b, btScalar tolerance)
|
||||
{
|
||||
btAssert(x.size() == b.size());
|
||||
reinitialize(b);
|
||||
|
||||
@@ -1,9 +1,15 @@
|
||||
//
|
||||
// btDeformableBackwardEulerObjective.cpp
|
||||
// BulletSoftBody
|
||||
//
|
||||
// Created by Xuchen Han on 7/9/19.
|
||||
//
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2016 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.
|
||||
*/
|
||||
|
||||
#include "btDeformableBackwardEulerObjective.h"
|
||||
|
||||
@@ -63,7 +69,6 @@ void btDeformableBackwardEulerObjective::multiply(const TVStack& x, TVStack& b)
|
||||
void btDeformableBackwardEulerObjective::updateVelocity(const TVStack& dv)
|
||||
{
|
||||
// only the velocity of the constrained nodes needs to be updated during CG solve
|
||||
// for (auto it : projection.m_constraints)
|
||||
for (int i = 0; i < projection.m_constraints.size(); ++i)
|
||||
{
|
||||
int index = projection.m_constraints.getKeyAtIndex(i).getUid1();
|
||||
@@ -112,7 +117,9 @@ btScalar btDeformableBackwardEulerObjective::computeNorm(const TVStack& residual
|
||||
void btDeformableBackwardEulerObjective::applyExplicitForce(TVStack& force)
|
||||
{
|
||||
for (int i = 0; i < m_lf.size(); ++i)
|
||||
{
|
||||
m_lf[i]->addScaledExplicitForce(m_dt, force);
|
||||
}
|
||||
applyForce(force, true);
|
||||
}
|
||||
|
||||
|
||||
@@ -1,9 +1,15 @@
|
||||
//
|
||||
// btDeformableBackwardEulerObjective.h
|
||||
// BulletSoftBody
|
||||
//
|
||||
// Created by Xuchen Han on 7/1/19.
|
||||
//
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2016 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 BT_BACKWARD_EULER_OBJECTIVE_H
|
||||
#define BT_BACKWARD_EULER_OBJECTIVE_H
|
||||
|
||||
@@ -1,9 +1,15 @@
|
||||
//
|
||||
// btDeformableBodySolver.cpp
|
||||
// BulletSoftBody
|
||||
//
|
||||
// Created by Xuchen Han on 7/9/19.
|
||||
//
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2016 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.
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
#include <limits>
|
||||
@@ -11,7 +17,7 @@
|
||||
|
||||
btDeformableBodySolver::btDeformableBodySolver()
|
||||
: m_numNodes(0)
|
||||
, cg(10)
|
||||
, m_cg(10)
|
||||
{
|
||||
m_objective = new btDeformableBackwardEulerObjective(m_softBodySet, m_backupVelocity);
|
||||
}
|
||||
@@ -40,7 +46,7 @@ void btDeformableBodySolver::solveConstraints(float solverdt)
|
||||
void btDeformableBodySolver::computeStep(TVStack& dv, const TVStack& residual)
|
||||
{
|
||||
btScalar tolerance = std::numeric_limits<float>::epsilon()* 1024 * m_objective->computeNorm(residual);
|
||||
cg.solve(*m_objective, dv, residual, tolerance);
|
||||
m_cg.solve(*m_objective, dv, residual, tolerance);
|
||||
}
|
||||
|
||||
void btDeformableBodySolver::reinitialize(const btAlignedObjectArray<btSoftBody *>& softBodies)
|
||||
|
||||
@@ -1,9 +1,15 @@
|
||||
//
|
||||
// btDeformableBodySolver.h
|
||||
// BulletSoftBody
|
||||
//
|
||||
// Created by Xuchen Han on 7/1/19.
|
||||
//
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2016 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 BT_DEFORMABLE_BODY_SOLVERS_H
|
||||
#define BT_DEFORMABLE_BODY_SOLVERS_H
|
||||
@@ -31,7 +37,7 @@ protected:
|
||||
|
||||
btAlignedObjectArray<btVector3> m_backupVelocity;
|
||||
btScalar m_dt;
|
||||
btConjugateGradient<btDeformableBackwardEulerObjective> cg;
|
||||
btConjugateGradient<btDeformableBackwardEulerObjective> m_cg;
|
||||
|
||||
|
||||
public:
|
||||
|
||||
@@ -1,9 +1,15 @@
|
||||
//
|
||||
// btDeformableContactProjection.cpp
|
||||
// BulletSoftBody
|
||||
//
|
||||
// Created by Xuchen Han on 7/4/19.
|
||||
//
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2016 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.
|
||||
*/
|
||||
|
||||
#include "btDeformableContactProjection.h"
|
||||
#include "btDeformableRigidDynamicsWorld.h"
|
||||
|
||||
@@ -1,9 +1,15 @@
|
||||
//
|
||||
// btDeformableContactProjection.h
|
||||
// BulletSoftBody
|
||||
//
|
||||
// Created by Xuchen Han on 7/4/19.
|
||||
//
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2016 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 BT_CONTACT_PROJECTION_H
|
||||
#define BT_CONTACT_PROJECTION_H
|
||||
@@ -15,9 +21,6 @@
|
||||
class btDeformableContactProjection : public btCGProjection
|
||||
{
|
||||
public:
|
||||
// std::unordered_map<btSoftBody::Node *, btAlignedObjectArray<DeformableContactConstraint> > m_constraints;
|
||||
// std::unordered_map<btSoftBody::Node *, btAlignedObjectArray<DeformableFrictionConstraint> > m_frictions;
|
||||
|
||||
// map from node index to constraints
|
||||
btHashMap<btHashInt, btAlignedObjectArray<DeformableContactConstraint> > m_constraints;
|
||||
btHashMap<btHashInt, btAlignedObjectArray<DeformableFrictionConstraint> >m_frictions;
|
||||
|
||||
@@ -1,9 +1,15 @@
|
||||
//
|
||||
// btDeformableGravityForce.h
|
||||
// BulletSoftBody
|
||||
//
|
||||
// Created by Xuchen Han on 7/21/19.
|
||||
//
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2016 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 BT_DEFORMABLE_GRAVITY_FORCE_H
|
||||
#define BT_DEFORMABLE_GRAVITY_FORCE_H
|
||||
@@ -13,18 +19,15 @@
|
||||
class btDeformableGravityForce : public btDeformableLagrangianForce
|
||||
{
|
||||
public:
|
||||
// using TVStack = btDeformableLagrangianForce::TVStack;
|
||||
typedef btAlignedObjectArray<btVector3> TVStack;
|
||||
btVector3 m_gravity;
|
||||
|
||||
btDeformableGravityForce(const btVector3& g) : m_gravity(g)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
virtual void addScaledImplicitForce(btScalar scale, TVStack& force)
|
||||
{
|
||||
// addScaledGravityForce(scale, force);
|
||||
}
|
||||
|
||||
virtual void addScaledExplicitForce(btScalar scale, TVStack& force)
|
||||
|
||||
@@ -1,9 +1,15 @@
|
||||
//
|
||||
// btDeformableLagrangianForce.h
|
||||
// BulletSoftBody
|
||||
//
|
||||
// Created by Xuchen Han on 7/1/19.
|
||||
//
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2016 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 BT_DEFORMABLE_LAGRANGIAN_FORCE_H
|
||||
#define BT_DEFORMABLE_LAGRANGIAN_FORCE_H
|
||||
|
||||
@@ -1,9 +1,15 @@
|
||||
//
|
||||
// btDeformableMassSpringForce.h
|
||||
// BulletSoftBody
|
||||
//
|
||||
// Created by Xuchen Gan on 7/1/19.
|
||||
//
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2016 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 BT_MASS_SPRING_H
|
||||
#define BT_MASS_SPRING_H
|
||||
|
||||
@@ -1,9 +1,15 @@
|
||||
//
|
||||
// btDeformableRigidDynamicsWorld.cpp
|
||||
// BulletSoftBody
|
||||
//
|
||||
// Created by Xuchen Han on 7/1/19.
|
||||
//
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2016 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.
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
#include "btDeformableRigidDynamicsWorld.h"
|
||||
@@ -13,7 +19,6 @@
|
||||
void btDeformableRigidDynamicsWorld::internalSingleStepSimulation(btScalar timeStep)
|
||||
{
|
||||
reinitialize(timeStep);
|
||||
// beforeSolverCallbacks(timeStep);
|
||||
// add gravity to velocity of rigid and multi bodys
|
||||
applyRigidBodyGravity(timeStep);
|
||||
|
||||
@@ -165,7 +170,7 @@ void btDeformableRigidDynamicsWorld::addSoftBody(btSoftBody* body, int collision
|
||||
void btDeformableRigidDynamicsWorld::predictUnconstraintMotion(btScalar timeStep)
|
||||
{
|
||||
btMultiBodyDynamicsWorld::predictUnconstraintMotion(timeStep);
|
||||
m_deformableBodySolver->predictMotion(float(timeStep));
|
||||
m_deformableBodySolver->predictMotion(timeStep);
|
||||
}
|
||||
|
||||
void btDeformableRigidDynamicsWorld::reinitialize(btScalar timeStep)
|
||||
@@ -181,8 +186,7 @@ void btDeformableRigidDynamicsWorld::reinitialize(btScalar timeStep)
|
||||
|
||||
void btDeformableRigidDynamicsWorld::applyRigidBodyGravity(btScalar timeStep)
|
||||
{
|
||||
// TODO: This is an ugly hack to get the desired gravity behavior.
|
||||
// gravity is applied in stepSimulation and then cleared here and then applied here and then cleared here again
|
||||
// Gravity is applied in stepSimulation and then cleared here and then applied here and then cleared here again
|
||||
// so that 1) gravity is applied to velocity before constraint solve and 2) gravity is applied in each substep
|
||||
// when there are multiple substeps
|
||||
clearForces();
|
||||
@@ -211,9 +215,6 @@ void btDeformableRigidDynamicsWorld::beforeSolverCallbacks(btScalar timeStep)
|
||||
{
|
||||
(*m_solverCallback)(m_internalTime, this);
|
||||
}
|
||||
|
||||
// for (int i = 0; i < m_beforeSolverCallbacks.size(); ++i)
|
||||
// m_beforeSolverCallbacks[i](m_internalTime, this);
|
||||
}
|
||||
|
||||
void btDeformableRigidDynamicsWorld::afterSolverCallbacks(btScalar timeStep)
|
||||
@@ -222,8 +223,6 @@ void btDeformableRigidDynamicsWorld::afterSolverCallbacks(btScalar timeStep)
|
||||
{
|
||||
(*m_solverCallback)(m_internalTime, this);
|
||||
}
|
||||
// for (int i = 0; i < m_beforeSolverCallbacks.size(); ++i)
|
||||
// m_beforeSolverCallbacks[i](m_internalTime, this);
|
||||
}
|
||||
|
||||
void btDeformableRigidDynamicsWorld::addForce(btSoftBody* psb, btDeformableLagrangianForce* force)
|
||||
|
||||
@@ -43,6 +43,9 @@ class btDeformableRigidDynamicsWorld : public btMultiBodyDynamicsWorld
|
||||
bool m_ownsSolver;
|
||||
btScalar m_internalTime;
|
||||
|
||||
typedef void (*btSolverCallback)(btScalar time, btDeformableRigidDynamicsWorld* world);
|
||||
btSolverCallback m_solverCallback;
|
||||
|
||||
protected:
|
||||
virtual void internalSingleStepSimulation(btScalar timeStep);
|
||||
|
||||
@@ -55,7 +58,7 @@ protected:
|
||||
public:
|
||||
btDeformableRigidDynamicsWorld(btDispatcher* dispatcher, btBroadphaseInterface* pairCache, btMultiBodyConstraintSolver* constraintSolver, btCollisionConfiguration* collisionConfiguration, btDeformableBodySolver* deformableBodySolver = 0)
|
||||
: btMultiBodyDynamicsWorld(dispatcher, pairCache, constraintSolver, collisionConfiguration),
|
||||
m_deformableBodySolver(deformableBodySolver)
|
||||
m_deformableBodySolver(deformableBodySolver), m_solverCallback(0)
|
||||
{
|
||||
m_drawFlags = fDrawFlags::Std;
|
||||
m_drawNodeTree = true;
|
||||
@@ -76,8 +79,7 @@ public:
|
||||
m_internalTime = 0.0;
|
||||
}
|
||||
// btAlignedObjectArray<std::function<void(btScalar, btDeformableRigidDynamicsWorld*)> > m_beforeSolverCallbacks;
|
||||
typedef void (*btSolverCallback)(btScalar time, btDeformableRigidDynamicsWorld* world);
|
||||
btSolverCallback m_solverCallback;
|
||||
|
||||
|
||||
void setSolverCallback(btSolverCallback cb)
|
||||
{
|
||||
|
||||
@@ -1,9 +1,15 @@
|
||||
//
|
||||
// btPreconditioner.h
|
||||
// BulletSoftBody
|
||||
//
|
||||
// Created by Xuchen Han on 7/18/19.
|
||||
//
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2016 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 BT_PRECONDITIONER_H
|
||||
#define BT_PRECONDITIONER_H
|
||||
|
||||
Reference in New Issue
Block a user