Skip to content

Commit 1adf52e

Browse files
committed
- added DamperJoint
- improved implementation of SliderJoint - improved implementation of TargetPositionMotorSliderJoint - improved implementation of TargetVelocityMotorSliderJoint - improved implementation of HingeJoint - improved implementation of TargetAngleMotorHingeJoint - improved implementation of TargetVelocityMotorHingeJoint
1 parent 1cc88ec commit 1adf52e

18 files changed

+1301
-1133
lines changed

CMake/Common.cmake

+2-2
Original file line numberDiff line numberDiff line change
@@ -15,9 +15,9 @@ set(PBD_BINARY_MINSIZEREL_POSTFIX "_ms" CACHE INTERNAL "Postfix for executables"
1515
if (WIN32)
1616
set(CMAKE_USE_RELATIVE_PATHS "1")
1717
# Set compiler flags
18-
set(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} /MP /openmp")
18+
set(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} /MP /openmp /bigobj")
1919
set(CMAKE_CXX_FLAGS_RELEASE "/MD /MP /Ox /Ob2 /Oi /Ot /D NDEBUG /openmp")
20-
set(CMAKE_CXX_FLAGS_RELWITHDEBINFO "/MD /Zi /MP /Ox /Ob2 /Oi /Ot /fp:fast /D NDEBUG /openmp")
20+
set(CMAKE_CXX_FLAGS_RELWITHDEBINFO "/MD /Zi /MP /Ox /Ob2 /Oi /Ot /D NDEBUG /openmp /bigobj")
2121
set(CMAKE_EXE_LINKER_FLAGS_RELEASE "/INCREMENTAL:NO")
2222
set(CMAKE_SHARED_LINKER_FLAGS_RELEASE "/INCREMENTAL:NO")
2323
set(CMAKE_STATIC_LINKER_FLAGS_RELEASE "/INCREMENTAL:NO")

Changelog.txt

+8
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,11 @@
1+
1.7.0
2+
- added DamperJoint
3+
- improved implementation of SliderJoint
4+
- improved implementation of TargetPositionMotorSliderJoint
5+
- improved implementation of TargetVelocityMotorSliderJoint
6+
- improved implementation of HingeJoint
7+
- improved implementation of TargetAngleMotorHingeJoint
8+
- improved implementation of TargetVelocityMotorHingeJoint
19
- use XPBD to implement an implicit spring
210
- added distance joint for rigid bodies
311
- small optimizations

Demos/Common/DemoBase.cpp

+68-19
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@ DemoBase::DemoBase()
3939
Utilities::logger.addSink(unique_ptr<Utilities::ConsoleSink>(new Utilities::ConsoleSink(Utilities::LogLevel::INFO)));
4040

4141
m_sceneLoader = nullptr;
42-
m_numberOfStepsPerRenderUpdate = 4;
42+
m_numberOfStepsPerRenderUpdate = 8;
4343
m_renderContacts = false;
4444
m_renderAABB = false;
4545
m_renderSDF = false;
@@ -128,6 +128,7 @@ void DemoBase::cleanup()
128128
m_scene.m_targetVelocityMotorSliderJointData.clear();
129129
m_scene.m_rigidBodySpringData.clear();
130130
m_scene.m_distanceJointData.clear();
131+
m_scene.m_damperJointData.clear();
131132
}
132133

133134
void DemoBase::init(int argc, char **argv, const char *demoName)
@@ -628,9 +629,17 @@ void DemoBase::renderBallOnLineJoint(BallOnLineJoint &bj)
628629

629630
void DemoBase::renderHingeJoint(HingeJoint &joint)
630631
{
631-
MiniGL::drawSphere(joint.m_jointInfo.col(6) - 0.5*joint.m_jointInfo.col(8), 0.1f, m_jointColor);
632-
MiniGL::drawSphere(joint.m_jointInfo.col(6) + 0.5*joint.m_jointInfo.col(8), 0.1f, m_jointColor);
633-
MiniGL::drawCylinder(joint.m_jointInfo.col(6) - 0.5*joint.m_jointInfo.col(8), joint.m_jointInfo.col(6) + 0.5*joint.m_jointInfo.col(8), m_jointColor, 0.05f);
632+
SimulationModel *model = Simulation::getCurrent()->getModel();
633+
const SimulationModel::RigidBodyVector &rigidBodies = model->getRigidBodies();
634+
RigidBody *rb = rigidBodies[joint.m_bodies[0]];
635+
636+
const Vector3r &c = joint.m_jointInfo.block<3, 1>(0, 4);
637+
const Vector3r &axis_local = joint.m_jointInfo.block<3, 1>(0, 6);
638+
const Vector3r axis = rb->getRotation().matrix() * axis_local;
639+
640+
MiniGL::drawSphere(c - 0.5*axis, 0.1f, m_jointColor);
641+
MiniGL::drawSphere(c + 0.5*axis, 0.1f, m_jointColor);
642+
MiniGL::drawCylinder(c - 0.5*axis, c + 0.5*axis, m_jointColor, 0.05f);
634643
}
635644

636645
void DemoBase::renderUniversalJoint(UniversalJoint &uj)
@@ -645,34 +654,71 @@ void DemoBase::renderUniversalJoint(UniversalJoint &uj)
645654

646655
void DemoBase::renderSliderJoint(SliderJoint &joint)
647656
{
648-
MiniGL::drawSphere(joint.m_jointInfo.col(6), 0.1f, m_jointColor);
649-
MiniGL::drawCylinder(joint.m_jointInfo.col(7) - joint.m_jointInfo.col(8), joint.m_jointInfo.col(7) + joint.m_jointInfo.col(8), m_jointColor, 0.05f);
657+
SimulationModel *model = Simulation::getCurrent()->getModel();
658+
const SimulationModel::RigidBodyVector &rigidBodies = model->getRigidBodies();
659+
RigidBody *rb = rigidBodies[joint.m_bodies[0]];
660+
661+
Quaternionr qR0;
662+
qR0.coeffs() = joint.m_jointInfo.col(1);
663+
const Vector3r &c = rb->getPosition();
664+
Vector3r axis = qR0.matrix().col(0);
665+
MiniGL::drawSphere(c, 0.1f, m_jointColor);
666+
MiniGL::drawCylinder(c - axis, c + axis, m_jointColor, 0.05f);
650667
}
651668

652669
void DemoBase::renderTargetPositionMotorSliderJoint(TargetPositionMotorSliderJoint &joint)
653670
{
654-
MiniGL::drawSphere(joint.m_jointInfo.col(6), 0.1f, m_jointColor);
655-
MiniGL::drawCylinder(joint.m_jointInfo.col(7) - joint.m_jointInfo.col(8), joint.m_jointInfo.col(7) + joint.m_jointInfo.col(8), m_jointColor, 0.05f);
671+
SimulationModel *model = Simulation::getCurrent()->getModel();
672+
const SimulationModel::RigidBodyVector &rigidBodies = model->getRigidBodies();
673+
RigidBody *rb = rigidBodies[joint.m_bodies[0]];
674+
675+
const Vector3r &c = rb->getPosition();
676+
Vector3r axis = joint.m_jointInfo.block<3, 1>(0, 1);
677+
MiniGL::drawSphere(c, 0.1f, m_jointColor);
678+
MiniGL::drawCylinder(c - axis, c + axis, m_jointColor, 0.05f);
656679
}
657680

658681
void DemoBase::renderTargetVelocityMotorSliderJoint(TargetVelocityMotorSliderJoint &joint)
659682
{
660-
MiniGL::drawSphere(joint.m_jointInfo.col(6), 0.1f, m_jointColor);
661-
MiniGL::drawCylinder(joint.m_jointInfo.col(7) - joint.m_jointInfo.col(8), joint.m_jointInfo.col(7) + joint.m_jointInfo.col(8), m_jointColor, 0.05f);
683+
SimulationModel *model = Simulation::getCurrent()->getModel();
684+
const SimulationModel::RigidBodyVector &rigidBodies = model->getRigidBodies();
685+
RigidBody *rb = rigidBodies[joint.m_bodies[0]];
686+
687+
Quaternionr qR0;
688+
qR0.coeffs() = joint.m_jointInfo.col(1);
689+
const Vector3r &c = rb->getPosition();
690+
Vector3r axis = qR0.matrix().col(0);
691+
MiniGL::drawSphere(c, 0.1f, m_jointColor);
692+
MiniGL::drawCylinder(c - axis, c + axis, m_jointColor, 0.05f);
662693
}
663694

664695
void DemoBase::renderTargetAngleMotorHingeJoint(TargetAngleMotorHingeJoint &joint)
665696
{
666-
MiniGL::drawSphere(joint.m_jointInfo.col(6) - 0.5*joint.m_jointInfo.col(8), 0.1f, m_jointColor);
667-
MiniGL::drawSphere(joint.m_jointInfo.col(6) + 0.5*joint.m_jointInfo.col(8), 0.1f, m_jointColor);
668-
MiniGL::drawCylinder(joint.m_jointInfo.col(6) - 0.5*joint.m_jointInfo.col(8), joint.m_jointInfo.col(6) + 0.5*joint.m_jointInfo.col(8), m_jointColor, 0.05f);
697+
SimulationModel *model = Simulation::getCurrent()->getModel();
698+
const SimulationModel::RigidBodyVector &rigidBodies = model->getRigidBodies();
699+
RigidBody *rb = rigidBodies[joint.m_bodies[0]];
700+
701+
const Vector3r &c = joint.m_jointInfo.block<3, 1>(0, 5);
702+
const Vector3r &axis_local = joint.m_jointInfo.block<3, 1>(0, 7);
703+
const Vector3r axis = rb->getRotation().matrix() * axis_local;
704+
705+
MiniGL::drawSphere(c - 0.5*axis, 0.1f, m_jointColor);
706+
MiniGL::drawSphere(c + 0.5*axis, 0.1f, m_jointColor);
707+
MiniGL::drawCylinder(c - 0.5*axis, c + 0.5*axis, m_jointColor, 0.05f);
669708
}
670709

671710
void DemoBase::renderTargetVelocityMotorHingeJoint(TargetVelocityMotorHingeJoint &joint)
672711
{
673-
MiniGL::drawSphere(joint.m_jointInfo.col(6) - 0.5*joint.m_jointInfo.col(8), 0.1f, m_jointColor);
674-
MiniGL::drawSphere(joint.m_jointInfo.col(6) + 0.5*joint.m_jointInfo.col(8), 0.1f, m_jointColor);
675-
MiniGL::drawCylinder(joint.m_jointInfo.col(6) - 0.5*joint.m_jointInfo.col(8), joint.m_jointInfo.col(6) + 0.5*joint.m_jointInfo.col(8), m_jointColor, 0.05f);
712+
SimulationModel *model = Simulation::getCurrent()->getModel();
713+
const SimulationModel::RigidBodyVector &rigidBodies = model->getRigidBodies();
714+
RigidBody *rb = rigidBodies[joint.m_bodies[0]];
715+
716+
const Vector3r &c = joint.m_jointInfo.block<3, 1>(0, 5);
717+
const Vector3r axis = joint.m_jointInfo.block<3, 1>(0, 7);
718+
719+
MiniGL::drawSphere(c - 0.5*axis, 0.1f, m_jointColor);
720+
MiniGL::drawSphere(c + 0.5*axis, 0.1f, m_jointColor);
721+
MiniGL::drawCylinder(c - 0.5*axis, c + 0.5*axis, m_jointColor, 0.05f);
676722
}
677723

678724
void DemoBase::renderRigidBodyContact(RigidBodyContactConstraint &cc)
@@ -722,13 +768,16 @@ void DemoBase::mouseMove(int x, int y, void *clientData)
722768
SimulationModel::RigidBodyVector &rb = model->getRigidBodies();
723769
for (size_t j = 0; j < base->m_selectedBodies.size(); j++)
724770
{
725-
if (rb[base->m_selectedBodies[j]]->getMass() != 0.0)
726-
rb[base->m_selectedBodies[j]]->getVelocity() += 1.0 / h * diff;
771+
const Real mass = rb[base->m_selectedBodies[j]]->getMass();
772+
if (mass != 0.0)
773+
rb[base->m_selectedBodies[j]]->getVelocity() += 3.0 / h * diff;
727774
}
728775
ParticleData &pd = model->getParticles();
729776
for (unsigned int j = 0; j < base->m_selectedParticles.size(); j++)
730777
{
731-
pd.getVelocity(base->m_selectedParticles[j]) += 5.0*diff / h;
778+
const Real mass = pd.getMass(base->m_selectedParticles[j]);
779+
if (mass != 0.0)
780+
pd.getVelocity(base->m_selectedParticles[j]) += 5.0*diff / h;
732781
}
733782
base->m_oldMousePos = mousePos;
734783
}

Demos/RigidBodyDemos/JointDemo.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -297,13 +297,13 @@ void createBodyModel()
297297
model->addTargetAngleMotorHingeJoint(12, 13, Vector3r(0.0, jointY, 1.0), Vector3r(1.0, 0.0, 0.0));
298298
model->addTargetVelocityMotorHingeJoint(13, 14, Vector3r(0.0, jointY, 3.0), Vector3r(0.0, 1.0, 0.0));
299299

300-
model->addSliderJoint(15, 16, Vector3r(4.0, jointY, 1.0), Vector3r(1.0, 0.0, 0.0));
300+
model->addSliderJoint(15, 16, Vector3r(1.0, 0.0, 0.0));
301301
model->addBallJoint(16, 17, Vector3r(4.25, jointY, 3.0));
302302

303-
model->addTargetPositionMotorSliderJoint(18, 19, Vector3r(8.0, jointY, 1.0), Vector3r(1.0, 0.0, 0.0));
303+
model->addTargetPositionMotorSliderJoint(18, 19, Vector3r(1.0, 0.0, 0.0));
304304
model->addBallJoint(19, 20, Vector3r(8.25, jointY, 3.0));
305305

306-
model->addTargetVelocityMotorSliderJoint(21, 22, Vector3r(12.0, jointY, 1.0), Vector3r(1.0, 0.0, 0.0));
306+
model->addTargetVelocityMotorSliderJoint(21, 22, Vector3r(1.0, 0.0, 0.0));
307307
model->addBallJoint(22, 23, Vector3r(12.25, jointY, 3.0));
308308

309309
jointY -= 5.5;

Demos/SceneLoaderDemo/SceneLoaderDemo.cpp

+9-3
Original file line numberDiff line numberDiff line change
@@ -1025,7 +1025,7 @@ void readScene(const bool readFile)
10251025
for (unsigned int i = 0; i < data.m_sliderJointData.size(); i++)
10261026
{
10271027
const SceneLoader::SliderJointData &jd = data.m_sliderJointData[i];
1028-
model->addSliderJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_position, jd.m_axis);
1028+
model->addSliderJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_axis);
10291029
}
10301030

10311031
for (unsigned int i = 0; i < data.m_rigidBodyParticleBallJointData.size(); i++)
@@ -1055,7 +1055,7 @@ void readScene(const bool readFile)
10551055
for (unsigned int i = 0; i < data.m_targetPositionMotorSliderJointData.size(); i++)
10561056
{
10571057
const SceneLoader::TargetPositionMotorSliderJointData &jd = data.m_targetPositionMotorSliderJointData[i];
1058-
model->addTargetPositionMotorSliderJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_position, jd.m_axis);
1058+
model->addTargetPositionMotorSliderJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_axis);
10591059
((MotorJoint*)constraints[constraints.size() - 1])->setTarget(jd.m_target);
10601060
((MotorJoint*)constraints[constraints.size() - 1])->setTargetSequence(jd.m_targetSequence);
10611061
((MotorJoint*)constraints[constraints.size() - 1])->setRepeatSequence(jd.m_repeat);
@@ -1064,12 +1064,18 @@ void readScene(const bool readFile)
10641064
for (unsigned int i = 0; i < data.m_targetVelocityMotorSliderJointData.size(); i++)
10651065
{
10661066
const SceneLoader::TargetVelocityMotorSliderJointData &jd = data.m_targetVelocityMotorSliderJointData[i];
1067-
model->addTargetVelocityMotorSliderJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_position, jd.m_axis);
1067+
model->addTargetVelocityMotorSliderJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_axis);
10681068
((MotorJoint*)constraints[constraints.size() - 1])->setTarget(jd.m_target);
10691069
((MotorJoint*)constraints[constraints.size() - 1])->setTargetSequence(jd.m_targetSequence);
10701070
((MotorJoint*)constraints[constraints.size() - 1])->setRepeatSequence(jd.m_repeat);
10711071
}
10721072

1073+
for (unsigned int i = 0; i < data.m_damperJointData.size(); i++)
1074+
{
1075+
const SceneLoader::DamperJointData &jd = data.m_damperJointData[i];
1076+
model->addDamperJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_axis, jd.m_stiffness);
1077+
}
1078+
10731079
for (unsigned int i = 0; i < data.m_rigidBodySpringData.size(); i++)
10741080
{
10751081
const SceneLoader::RigidBodySpringData &jd = data.m_rigidBodySpringData[i];

Demos/StiffRodsDemos/DirectPositionBasedSolverForStiffRodsDemo.cpp

+21-3
Original file line numberDiff line numberDiff line change
@@ -1230,7 +1230,7 @@ void readScene()
12301230
for (unsigned int i = 0; i < data.m_sliderJointData.size(); i++)
12311231
{
12321232
const SceneLoader::SliderJointData &jd = data.m_sliderJointData[i];
1233-
model->addSliderJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_position, jd.m_axis);
1233+
model->addSliderJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_axis);
12341234
}
12351235

12361236
for (unsigned int i = 0; i < data.m_rigidBodyParticleBallJointData.size(); i++)
@@ -1260,7 +1260,7 @@ void readScene()
12601260
for (unsigned int i = 0; i < data.m_targetPositionMotorSliderJointData.size(); i++)
12611261
{
12621262
const SceneLoader::TargetPositionMotorSliderJointData &jd = data.m_targetPositionMotorSliderJointData[i];
1263-
model->addTargetPositionMotorSliderJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_position, jd.m_axis);
1263+
model->addTargetPositionMotorSliderJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_axis);
12641264
((MotorJoint*)constraints[constraints.size() - 1])->setTarget(jd.m_target);
12651265
((MotorJoint*)constraints[constraints.size() - 1])->setTargetSequence(jd.m_targetSequence);
12661266
((MotorJoint*)constraints[constraints.size() - 1])->setRepeatSequence(jd.m_repeat);
@@ -1269,11 +1269,29 @@ void readScene()
12691269
for (unsigned int i = 0; i < data.m_targetVelocityMotorSliderJointData.size(); i++)
12701270
{
12711271
const SceneLoader::TargetVelocityMotorSliderJointData &jd = data.m_targetVelocityMotorSliderJointData[i];
1272-
model->addTargetVelocityMotorSliderJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_position, jd.m_axis);
1272+
model->addTargetVelocityMotorSliderJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_axis);
12731273
((MotorJoint*)constraints[constraints.size() - 1])->setTarget(jd.m_target);
12741274
((MotorJoint*)constraints[constraints.size() - 1])->setTargetSequence(jd.m_targetSequence);
12751275
((MotorJoint*)constraints[constraints.size() - 1])->setRepeatSequence(jd.m_repeat);
12761276
}
1277+
1278+
for (unsigned int i = 0; i < data.m_damperJointData.size(); i++)
1279+
{
1280+
const SceneLoader::DamperJointData &jd = data.m_damperJointData[i];
1281+
model->addDamperJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_axis, jd.m_stiffness);
1282+
}
1283+
1284+
for (unsigned int i = 0; i < data.m_rigidBodySpringData.size(); i++)
1285+
{
1286+
const SceneLoader::RigidBodySpringData &jd = data.m_rigidBodySpringData[i];
1287+
model->addRigidBodySpring(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_position1, jd.m_position2, jd.m_stiffness);
1288+
}
1289+
1290+
for (unsigned int i = 0; i < data.m_distanceJointData.size(); i++)
1291+
{
1292+
const SceneLoader::DistanceJointData &jd = data.m_distanceJointData[i];
1293+
model->addDistanceJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_position1, jd.m_position2);
1294+
}
12771295
}
12781296

12791297
void TW_CALL setContactTolerance(const void *value, void *clientData)

0 commit comments

Comments
 (0)