Skip to content

Commit

Permalink
- added DamperJoint
Browse files Browse the repository at this point in the history
- improved implementation of SliderJoint
- improved implementation of TargetPositionMotorSliderJoint
- improved implementation of TargetVelocityMotorSliderJoint
- improved implementation of HingeJoint
- improved implementation of TargetAngleMotorHingeJoint
- improved implementation of TargetVelocityMotorHingeJoint
  • Loading branch information
janbender committed Sep 2, 2019
1 parent 1cc88ec commit 1adf52e
Show file tree
Hide file tree
Showing 18 changed files with 1,301 additions and 1,133 deletions.
4 changes: 2 additions & 2 deletions CMake/Common.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -15,9 +15,9 @@ set(PBD_BINARY_MINSIZEREL_POSTFIX "_ms" CACHE INTERNAL "Postfix for executables"
if (WIN32)
set(CMAKE_USE_RELATIVE_PATHS "1")
# Set compiler flags
set(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} /MP /openmp")
set(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} /MP /openmp /bigobj")
set(CMAKE_CXX_FLAGS_RELEASE "/MD /MP /Ox /Ob2 /Oi /Ot /D NDEBUG /openmp")
set(CMAKE_CXX_FLAGS_RELWITHDEBINFO "/MD /Zi /MP /Ox /Ob2 /Oi /Ot /fp:fast /D NDEBUG /openmp")
set(CMAKE_CXX_FLAGS_RELWITHDEBINFO "/MD /Zi /MP /Ox /Ob2 /Oi /Ot /D NDEBUG /openmp /bigobj")
set(CMAKE_EXE_LINKER_FLAGS_RELEASE "/INCREMENTAL:NO")
set(CMAKE_SHARED_LINKER_FLAGS_RELEASE "/INCREMENTAL:NO")
set(CMAKE_STATIC_LINKER_FLAGS_RELEASE "/INCREMENTAL:NO")
Expand Down
8 changes: 8 additions & 0 deletions Changelog.txt
Original file line number Diff line number Diff line change
@@ -1,3 +1,11 @@
1.7.0
- 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
- use XPBD to implement an implicit spring
- added distance joint for rigid bodies
- small optimizations
Expand Down
87 changes: 68 additions & 19 deletions Demos/Common/DemoBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ DemoBase::DemoBase()
Utilities::logger.addSink(unique_ptr<Utilities::ConsoleSink>(new Utilities::ConsoleSink(Utilities::LogLevel::INFO)));

m_sceneLoader = nullptr;
m_numberOfStepsPerRenderUpdate = 4;
m_numberOfStepsPerRenderUpdate = 8;
m_renderContacts = false;
m_renderAABB = false;
m_renderSDF = false;
Expand Down Expand Up @@ -128,6 +128,7 @@ void DemoBase::cleanup()
m_scene.m_targetVelocityMotorSliderJointData.clear();
m_scene.m_rigidBodySpringData.clear();
m_scene.m_distanceJointData.clear();
m_scene.m_damperJointData.clear();
}

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

void DemoBase::renderHingeJoint(HingeJoint &joint)
{
MiniGL::drawSphere(joint.m_jointInfo.col(6) - 0.5*joint.m_jointInfo.col(8), 0.1f, m_jointColor);
MiniGL::drawSphere(joint.m_jointInfo.col(6) + 0.5*joint.m_jointInfo.col(8), 0.1f, m_jointColor);
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);
SimulationModel *model = Simulation::getCurrent()->getModel();
const SimulationModel::RigidBodyVector &rigidBodies = model->getRigidBodies();
RigidBody *rb = rigidBodies[joint.m_bodies[0]];

const Vector3r &c = joint.m_jointInfo.block<3, 1>(0, 4);
const Vector3r &axis_local = joint.m_jointInfo.block<3, 1>(0, 6);
const Vector3r axis = rb->getRotation().matrix() * axis_local;

MiniGL::drawSphere(c - 0.5*axis, 0.1f, m_jointColor);
MiniGL::drawSphere(c + 0.5*axis, 0.1f, m_jointColor);
MiniGL::drawCylinder(c - 0.5*axis, c + 0.5*axis, m_jointColor, 0.05f);
}

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

void DemoBase::renderSliderJoint(SliderJoint &joint)
{
MiniGL::drawSphere(joint.m_jointInfo.col(6), 0.1f, m_jointColor);
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);
SimulationModel *model = Simulation::getCurrent()->getModel();
const SimulationModel::RigidBodyVector &rigidBodies = model->getRigidBodies();
RigidBody *rb = rigidBodies[joint.m_bodies[0]];

Quaternionr qR0;
qR0.coeffs() = joint.m_jointInfo.col(1);
const Vector3r &c = rb->getPosition();
Vector3r axis = qR0.matrix().col(0);
MiniGL::drawSphere(c, 0.1f, m_jointColor);
MiniGL::drawCylinder(c - axis, c + axis, m_jointColor, 0.05f);
}

void DemoBase::renderTargetPositionMotorSliderJoint(TargetPositionMotorSliderJoint &joint)
{
MiniGL::drawSphere(joint.m_jointInfo.col(6), 0.1f, m_jointColor);
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);
SimulationModel *model = Simulation::getCurrent()->getModel();
const SimulationModel::RigidBodyVector &rigidBodies = model->getRigidBodies();
RigidBody *rb = rigidBodies[joint.m_bodies[0]];

const Vector3r &c = rb->getPosition();
Vector3r axis = joint.m_jointInfo.block<3, 1>(0, 1);
MiniGL::drawSphere(c, 0.1f, m_jointColor);
MiniGL::drawCylinder(c - axis, c + axis, m_jointColor, 0.05f);
}

void DemoBase::renderTargetVelocityMotorSliderJoint(TargetVelocityMotorSliderJoint &joint)
{
MiniGL::drawSphere(joint.m_jointInfo.col(6), 0.1f, m_jointColor);
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);
SimulationModel *model = Simulation::getCurrent()->getModel();
const SimulationModel::RigidBodyVector &rigidBodies = model->getRigidBodies();
RigidBody *rb = rigidBodies[joint.m_bodies[0]];

Quaternionr qR0;
qR0.coeffs() = joint.m_jointInfo.col(1);
const Vector3r &c = rb->getPosition();
Vector3r axis = qR0.matrix().col(0);
MiniGL::drawSphere(c, 0.1f, m_jointColor);
MiniGL::drawCylinder(c - axis, c + axis, m_jointColor, 0.05f);
}

void DemoBase::renderTargetAngleMotorHingeJoint(TargetAngleMotorHingeJoint &joint)
{
MiniGL::drawSphere(joint.m_jointInfo.col(6) - 0.5*joint.m_jointInfo.col(8), 0.1f, m_jointColor);
MiniGL::drawSphere(joint.m_jointInfo.col(6) + 0.5*joint.m_jointInfo.col(8), 0.1f, m_jointColor);
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);
SimulationModel *model = Simulation::getCurrent()->getModel();
const SimulationModel::RigidBodyVector &rigidBodies = model->getRigidBodies();
RigidBody *rb = rigidBodies[joint.m_bodies[0]];

const Vector3r &c = joint.m_jointInfo.block<3, 1>(0, 5);
const Vector3r &axis_local = joint.m_jointInfo.block<3, 1>(0, 7);
const Vector3r axis = rb->getRotation().matrix() * axis_local;

MiniGL::drawSphere(c - 0.5*axis, 0.1f, m_jointColor);
MiniGL::drawSphere(c + 0.5*axis, 0.1f, m_jointColor);
MiniGL::drawCylinder(c - 0.5*axis, c + 0.5*axis, m_jointColor, 0.05f);
}

void DemoBase::renderTargetVelocityMotorHingeJoint(TargetVelocityMotorHingeJoint &joint)
{
MiniGL::drawSphere(joint.m_jointInfo.col(6) - 0.5*joint.m_jointInfo.col(8), 0.1f, m_jointColor);
MiniGL::drawSphere(joint.m_jointInfo.col(6) + 0.5*joint.m_jointInfo.col(8), 0.1f, m_jointColor);
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);
SimulationModel *model = Simulation::getCurrent()->getModel();
const SimulationModel::RigidBodyVector &rigidBodies = model->getRigidBodies();
RigidBody *rb = rigidBodies[joint.m_bodies[0]];

const Vector3r &c = joint.m_jointInfo.block<3, 1>(0, 5);
const Vector3r axis = joint.m_jointInfo.block<3, 1>(0, 7);

MiniGL::drawSphere(c - 0.5*axis, 0.1f, m_jointColor);
MiniGL::drawSphere(c + 0.5*axis, 0.1f, m_jointColor);
MiniGL::drawCylinder(c - 0.5*axis, c + 0.5*axis, m_jointColor, 0.05f);
}

void DemoBase::renderRigidBodyContact(RigidBodyContactConstraint &cc)
Expand Down Expand Up @@ -722,13 +768,16 @@ void DemoBase::mouseMove(int x, int y, void *clientData)
SimulationModel::RigidBodyVector &rb = model->getRigidBodies();
for (size_t j = 0; j < base->m_selectedBodies.size(); j++)
{
if (rb[base->m_selectedBodies[j]]->getMass() != 0.0)
rb[base->m_selectedBodies[j]]->getVelocity() += 1.0 / h * diff;
const Real mass = rb[base->m_selectedBodies[j]]->getMass();
if (mass != 0.0)
rb[base->m_selectedBodies[j]]->getVelocity() += 3.0 / h * diff;
}
ParticleData &pd = model->getParticles();
for (unsigned int j = 0; j < base->m_selectedParticles.size(); j++)
{
pd.getVelocity(base->m_selectedParticles[j]) += 5.0*diff / h;
const Real mass = pd.getMass(base->m_selectedParticles[j]);
if (mass != 0.0)
pd.getVelocity(base->m_selectedParticles[j]) += 5.0*diff / h;
}
base->m_oldMousePos = mousePos;
}
Expand Down
6 changes: 3 additions & 3 deletions Demos/RigidBodyDemos/JointDemo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -297,13 +297,13 @@ void createBodyModel()
model->addTargetAngleMotorHingeJoint(12, 13, Vector3r(0.0, jointY, 1.0), Vector3r(1.0, 0.0, 0.0));
model->addTargetVelocityMotorHingeJoint(13, 14, Vector3r(0.0, jointY, 3.0), Vector3r(0.0, 1.0, 0.0));

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

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

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

jointY -= 5.5;
Expand Down
12 changes: 9 additions & 3 deletions Demos/SceneLoaderDemo/SceneLoaderDemo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1025,7 +1025,7 @@ void readScene(const bool readFile)
for (unsigned int i = 0; i < data.m_sliderJointData.size(); i++)
{
const SceneLoader::SliderJointData &jd = data.m_sliderJointData[i];
model->addSliderJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_position, jd.m_axis);
model->addSliderJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_axis);
}

for (unsigned int i = 0; i < data.m_rigidBodyParticleBallJointData.size(); i++)
Expand Down Expand Up @@ -1055,7 +1055,7 @@ void readScene(const bool readFile)
for (unsigned int i = 0; i < data.m_targetPositionMotorSliderJointData.size(); i++)
{
const SceneLoader::TargetPositionMotorSliderJointData &jd = data.m_targetPositionMotorSliderJointData[i];
model->addTargetPositionMotorSliderJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_position, jd.m_axis);
model->addTargetPositionMotorSliderJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_axis);
((MotorJoint*)constraints[constraints.size() - 1])->setTarget(jd.m_target);
((MotorJoint*)constraints[constraints.size() - 1])->setTargetSequence(jd.m_targetSequence);
((MotorJoint*)constraints[constraints.size() - 1])->setRepeatSequence(jd.m_repeat);
Expand All @@ -1064,12 +1064,18 @@ void readScene(const bool readFile)
for (unsigned int i = 0; i < data.m_targetVelocityMotorSliderJointData.size(); i++)
{
const SceneLoader::TargetVelocityMotorSliderJointData &jd = data.m_targetVelocityMotorSliderJointData[i];
model->addTargetVelocityMotorSliderJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_position, jd.m_axis);
model->addTargetVelocityMotorSliderJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_axis);
((MotorJoint*)constraints[constraints.size() - 1])->setTarget(jd.m_target);
((MotorJoint*)constraints[constraints.size() - 1])->setTargetSequence(jd.m_targetSequence);
((MotorJoint*)constraints[constraints.size() - 1])->setRepeatSequence(jd.m_repeat);
}

for (unsigned int i = 0; i < data.m_damperJointData.size(); i++)
{
const SceneLoader::DamperJointData &jd = data.m_damperJointData[i];
model->addDamperJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_axis, jd.m_stiffness);
}

for (unsigned int i = 0; i < data.m_rigidBodySpringData.size(); i++)
{
const SceneLoader::RigidBodySpringData &jd = data.m_rigidBodySpringData[i];
Expand Down
24 changes: 21 additions & 3 deletions Demos/StiffRodsDemos/DirectPositionBasedSolverForStiffRodsDemo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1230,7 +1230,7 @@ void readScene()
for (unsigned int i = 0; i < data.m_sliderJointData.size(); i++)
{
const SceneLoader::SliderJointData &jd = data.m_sliderJointData[i];
model->addSliderJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_position, jd.m_axis);
model->addSliderJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_axis);
}

for (unsigned int i = 0; i < data.m_rigidBodyParticleBallJointData.size(); i++)
Expand Down Expand Up @@ -1260,7 +1260,7 @@ void readScene()
for (unsigned int i = 0; i < data.m_targetPositionMotorSliderJointData.size(); i++)
{
const SceneLoader::TargetPositionMotorSliderJointData &jd = data.m_targetPositionMotorSliderJointData[i];
model->addTargetPositionMotorSliderJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_position, jd.m_axis);
model->addTargetPositionMotorSliderJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_axis);
((MotorJoint*)constraints[constraints.size() - 1])->setTarget(jd.m_target);
((MotorJoint*)constraints[constraints.size() - 1])->setTargetSequence(jd.m_targetSequence);
((MotorJoint*)constraints[constraints.size() - 1])->setRepeatSequence(jd.m_repeat);
Expand All @@ -1269,11 +1269,29 @@ void readScene()
for (unsigned int i = 0; i < data.m_targetVelocityMotorSliderJointData.size(); i++)
{
const SceneLoader::TargetVelocityMotorSliderJointData &jd = data.m_targetVelocityMotorSliderJointData[i];
model->addTargetVelocityMotorSliderJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_position, jd.m_axis);
model->addTargetVelocityMotorSliderJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_axis);
((MotorJoint*)constraints[constraints.size() - 1])->setTarget(jd.m_target);
((MotorJoint*)constraints[constraints.size() - 1])->setTargetSequence(jd.m_targetSequence);
((MotorJoint*)constraints[constraints.size() - 1])->setRepeatSequence(jd.m_repeat);
}

for (unsigned int i = 0; i < data.m_damperJointData.size(); i++)
{
const SceneLoader::DamperJointData &jd = data.m_damperJointData[i];
model->addDamperJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_axis, jd.m_stiffness);
}

for (unsigned int i = 0; i < data.m_rigidBodySpringData.size(); i++)
{
const SceneLoader::RigidBodySpringData &jd = data.m_rigidBodySpringData[i];
model->addRigidBodySpring(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_position1, jd.m_position2, jd.m_stiffness);
}

for (unsigned int i = 0; i < data.m_distanceJointData.size(); i++)
{
const SceneLoader::DistanceJointData &jd = data.m_distanceJointData[i];
model->addDistanceJoint(id_index[jd.m_bodyID[0]], id_index[jd.m_bodyID[1]], jd.m_position1, jd.m_position2);
}
}

void TW_CALL setContactTolerance(const void *value, void *clientData)
Expand Down
Loading

0 comments on commit 1adf52e

Please sign in to comment.