mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-14 05:40:05 +00:00
address PR comment and tune parameters for cloth
This commit is contained in:
parent
4ab0387262
commit
6a8973d2f4
@ -424,12 +424,13 @@ public:
|
|||||||
m_robotSim.setGravity(btVector3(0, 0, -10));
|
m_robotSim.setGravity(btVector3(0, 0, -10));
|
||||||
|
|
||||||
m_robotSim.setGravity(btVector3(0, 0, -10));
|
m_robotSim.setGravity(btVector3(0, 0, -10));
|
||||||
b3RobotSimulatorLoadDeformableBodyArgs args(1, .01, 0.02);
|
b3RobotSimulatorLoadDeformableBodyArgs args(2, .01, 0.006);
|
||||||
args.m_springElasticStiffness = 1;
|
args.m_springElasticStiffness = .1;
|
||||||
args.m_springDampingStiffness = .001;
|
args.m_springDampingStiffness = .0004;
|
||||||
args.m_springBendingStiffness = .2;
|
args.m_springBendingStiffness = 1;
|
||||||
args.m_frictionCoeff = 2;
|
args.m_frictionCoeff = 1;
|
||||||
args.m_useSelfCollision = false;
|
args.m_useSelfCollision = false;
|
||||||
|
// args.m_useFaceContact = true;
|
||||||
args.m_useBendingSprings = true;
|
args.m_useBendingSprings = true;
|
||||||
args.m_startPosition.setValue(0, 0, 0);
|
args.m_startPosition.setValue(0, 0, 0);
|
||||||
args.m_startOrientation.setValue(0, 0, 1, 1);
|
args.m_startOrientation.setValue(0, 0, 1, 1);
|
||||||
@ -475,6 +476,7 @@ public:
|
|||||||
revoluteJoint2.m_jointType = ePoint2PointType;
|
revoluteJoint2.m_jointType = ePoint2PointType;
|
||||||
m_robotSim.createConstraint(0, 2, 0, 4, &revoluteJoint1);
|
m_robotSim.createConstraint(0, 2, 0, 4, &revoluteJoint1);
|
||||||
m_robotSim.createConstraint(0, 3, 0, 6, &revoluteJoint2);
|
m_robotSim.createConstraint(0, 3, 0, 6, &revoluteJoint2);
|
||||||
|
m_robotSim.setNumSimulationSubSteps(8);
|
||||||
}
|
}
|
||||||
|
|
||||||
if ((m_options & eSOFTBODY_MULTIBODY_COUPLING) != 0)
|
if ((m_options & eSOFTBODY_MULTIBODY_COUPLING) != 0)
|
||||||
|
@ -1178,8 +1178,14 @@ void b3RobotSimulatorClientAPI_NoDirect::loadDeformableBody(const std::string& f
|
|||||||
b3LoadSoftBodySetScale(command, args.m_scale);
|
b3LoadSoftBodySetScale(command, args.m_scale);
|
||||||
b3LoadSoftBodySetMass(command, args.m_mass);
|
b3LoadSoftBodySetMass(command, args.m_mass);
|
||||||
b3LoadSoftBodySetCollisionMargin(command, args.m_collisionMargin);
|
b3LoadSoftBodySetCollisionMargin(command, args.m_collisionMargin);
|
||||||
b3LoadSoftBodyAddNeoHookeanForce(command, args.m_NeoHookeanMu, args.m_NeoHookeanLambda, args.m_NeoHookeanDamping);
|
if (args.m_NeoHookeanMu > 0)
|
||||||
b3LoadSoftBodyAddMassSpringForce(command, args.m_springElasticStiffness, args.m_springDampingStiffness);
|
{
|
||||||
|
b3LoadSoftBodyAddNeoHookeanForce(command, args.m_NeoHookeanMu, args.m_NeoHookeanLambda, args.m_NeoHookeanDamping);
|
||||||
|
}
|
||||||
|
if (args.m_springElasticStiffness > 0)
|
||||||
|
{
|
||||||
|
b3LoadSoftBodyAddMassSpringForce(command, args.m_springElasticStiffness, args.m_springDampingStiffness);
|
||||||
|
}
|
||||||
b3LoadSoftBodySetSelfCollision(command, args.m_useSelfCollision);
|
b3LoadSoftBodySetSelfCollision(command, args.m_useSelfCollision);
|
||||||
b3LoadSoftBodyUseFaceContact(command, args.m_useFaceContact);
|
b3LoadSoftBodyUseFaceContact(command, args.m_useFaceContact);
|
||||||
b3LoadSoftBodySetFrictionCoefficient(command, args.m_frictionCoeff);
|
b3LoadSoftBodySetFrictionCoefficient(command, args.m_frictionCoeff);
|
||||||
|
@ -113,7 +113,16 @@ struct b3RobotSimulatorLoadDeformableBodyArgs
|
|||||||
m_startOrientation(startOrn),
|
m_startOrientation(startOrn),
|
||||||
m_scale(scale),
|
m_scale(scale),
|
||||||
m_mass(mass),
|
m_mass(mass),
|
||||||
m_collisionMargin(collisionMargin)
|
m_collisionMargin(collisionMargin),
|
||||||
|
m_springElasticStiffness(-1),
|
||||||
|
m_springDampingStiffness(-1),
|
||||||
|
m_springBendingStiffness(-1),
|
||||||
|
m_NeoHookeanMu(-1),
|
||||||
|
m_NeoHookeanDamping(-1),
|
||||||
|
m_useSelfCollision(false),
|
||||||
|
m_useFaceContact(false),
|
||||||
|
m_useBendingSprings(false),
|
||||||
|
m_frictionCoeff(0)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user