Skip to content

Commit

Permalink
Use a function-local static variable to replace globals
Browse files Browse the repository at this point in the history
Signed-off-by: Addisu Z. Taddese <addisu@openrobotics.org>
  • Loading branch information
azeey committed Oct 4, 2021
1 parent 11876d5 commit 8495a45
Show file tree
Hide file tree
Showing 2 changed files with 48 additions and 22 deletions.
44 changes: 29 additions & 15 deletions dart/constraint/ConstraintSolver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,11 +61,24 @@ namespace constraint {

using namespace dynamics;

// These two globals are a hack made to retain ABI compatibility.
// This global and the function that immediately follows are a hack made to
// retain ABI compatibility.
// TODO(anyone): Revert e95a6 in a future ABI-breaking version.
std::mutex gContactSurfaceHandlersMutex;
std::unordered_map<const ConstraintSolver*, ContactSurfaceHandlerPtr>
gContactSurfaceHandlers;

std::unordered_map<const ConstraintSolver*, ContactSurfaceHandlerPtr>&
getContactSurfaceHandlers()
{
// This object is used as a global variable in this file. Since the type has a
// non-trivial destructor, we avoid making it a global. Instead, we use the
// construct-on-first-use idiom where we allocate it here and never delete it
// per the Google style and C++ Core Guidelines.
// https://isocpp.org/wiki/faq/ctors#static-init-order-on-first-use
static auto& contactSurfaceHandlers
= *new std::
unordered_map<const ConstraintSolver*, ContactSurfaceHandlerPtr>;
return contactSurfaceHandlers;
}

//==============================================================================
ConstraintSolver::ConstraintSolver(double timeStep)
Expand All @@ -87,7 +100,7 @@ ConstraintSolver::ConstraintSolver(double timeStep)

{
std::lock_guard<std::mutex> lock(gContactSurfaceHandlersMutex);
gContactSurfaceHandlers[this] =
getContactSurfaceHandlers()[this] =
std::make_shared<DefaultContactSurfaceHandler>();
}
}
Expand All @@ -110,7 +123,7 @@ ConstraintSolver::ConstraintSolver()

{
std::lock_guard<std::mutex> lock(gContactSurfaceHandlersMutex);
gContactSurfaceHandlers[this] =
getContactSurfaceHandlers()[this] =
std::make_shared<DefaultContactSurfaceHandler>();
}
}
Expand All @@ -119,7 +132,7 @@ ConstraintSolver::ConstraintSolver()
ConstraintSolver::~ConstraintSolver()
{
std::lock_guard<std::mutex> lock(gContactSurfaceHandlersMutex);
gContactSurfaceHandlers.erase(this);
getContactSurfaceHandlers().erase(this);
}

//==============================================================================
Expand Down Expand Up @@ -420,7 +433,7 @@ void ConstraintSolver::setFromOtherConstraintSolver(

{
std::lock_guard<std::mutex> lock(gContactSurfaceHandlersMutex);
gContactSurfaceHandlers[this] = gContactSurfaceHandlers[&other];
getContactSurfaceHandlers()[this] = getContactSurfaceHandlers()[&other];
}
}

Expand Down Expand Up @@ -591,8 +604,9 @@ void ConstraintSolver::updateConstraints()
if (it != contactPairMap.end())
numContacts = it->second;

auto contactConstraint = gContactSurfaceHandlers[this]->createConstraint(
*contact, numContacts, mTimeStep);
auto contactConstraint
= getContactSurfaceHandlers()[this]->createConstraint(
*contact, numContacts, mTimeStep);

mContactConstraints.push_back(contactConstraint);

Expand Down Expand Up @@ -790,7 +804,7 @@ ConstraintSolver::getLastContactSurfaceHandler() const
{
{
std::lock_guard<std::mutex> lock(gContactSurfaceHandlersMutex);
return gContactSurfaceHandlers[this];
return getContactSurfaceHandlers()[this];
}
}

Expand All @@ -800,8 +814,8 @@ void ConstraintSolver::addContactSurfaceHandler(
{
{
std::lock_guard<std::mutex> lock(gContactSurfaceHandlersMutex);
handler->setParent(gContactSurfaceHandlers[this]);
gContactSurfaceHandlers[this] = std::move(handler);
handler->setParent(getContactSurfaceHandlers()[this]);
getContactSurfaceHandlers()[this] = std::move(handler);
}
}

Expand All @@ -811,7 +825,7 @@ bool ConstraintSolver::removeContactSurfaceHandler(
{
bool found = false;
std::lock_guard<std::mutex> lock(gContactSurfaceHandlersMutex);
ContactSurfaceHandlerPtr current = gContactSurfaceHandlers[this];
ContactSurfaceHandlerPtr current = getContactSurfaceHandlers()[this];
ContactSurfaceHandlerPtr previous = nullptr;
while (current != nullptr)
{
Expand All @@ -820,15 +834,15 @@ bool ConstraintSolver::removeContactSurfaceHandler(
if (previous != nullptr)
previous->mParent = current->mParent;
else
gContactSurfaceHandlers[this] = current->mParent;
getContactSurfaceHandlers()[this] = current->mParent;
found = true;
break;
}
previous = current;
current = current->mParent;
}

if (gContactSurfaceHandlers[this] == nullptr)
if (getContactSurfaceHandlers()[this] == nullptr)
dterr << "No contact surface handler remained. This is an error. Add at "
<< "least DefaultContactSurfaceHandler." << std::endl;

Expand Down
26 changes: 19 additions & 7 deletions dart/constraint/ContactConstraint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,11 +59,23 @@ double ContactConstraint::mErrorReductionParameter = DART_ERP;
double ContactConstraint::mMaxErrorReductionVelocity = DART_MAX_ERV;
double ContactConstraint::mConstraintForceMixing = DART_CFM;

// These two globals are a hack made to retain ABI compatibility.
// This global and the function that immediately follows are a hack made to
// retain ABI compatibility.
// TODO(anyone): Revert e95a6 in a future ABI-breaking version.
std::mutex gContactSurfaceMotionVelocitiesMutex;
std::unordered_map<ContactConstraint*, Eigen::Vector3d>
gContactSurfaceMotionVelocities;

std::unordered_map<ContactConstraint*, Eigen::Vector3d>&
getContactSurfaceMotionVelocities()
{
// This object is used as a global variable in this file. Since the type has a
// non-trivial destructor, we avoid making it a global. Instead, we use the
// construct-on-first-use idiom where we allocate it here and never delete it
// per the Google style and C++ Core Guidelines.
// https://isocpp.org/wiki/faq/ctors#static-init-order-on-first-use
static auto& contactSurfaceMotionVelocities
= *new std::unordered_map<ContactConstraint*, Eigen::Vector3d>;
return contactSurfaceMotionVelocities;
}

//==============================================================================
ContactConstraint::ContactConstraint(
Expand Down Expand Up @@ -136,7 +148,7 @@ ContactConstraint::ContactConstraint(

{
std::lock_guard<std::mutex> lock(gContactSurfaceMotionVelocitiesMutex);
gContactSurfaceMotionVelocities[this] =
getContactSurfaceMotionVelocities()[this] =
contactSurfaceParams.mContactSurfaceMotionVelocity;
}

Expand Down Expand Up @@ -248,7 +260,7 @@ ContactConstraint::ContactConstraint(
ContactConstraint::~ContactConstraint()
{
std::lock_guard<std::mutex> lock(gContactSurfaceMotionVelocitiesMutex);
gContactSurfaceMotionVelocities.erase(this);
getContactSurfaceMotionVelocities().erase(this);
}

//==============================================================================
Expand Down Expand Up @@ -431,7 +443,7 @@ void ContactConstraint::getInformation(ConstraintInfo* info)
info->b[0] += bouncingVelocity;
{
std::lock_guard<std::mutex> lock(gContactSurfaceMotionVelocitiesMutex);
const auto& surfaceVelocity = gContactSurfaceMotionVelocities[this];
const auto& surfaceVelocity = getContactSurfaceMotionVelocities()[this];
info->b[0] += surfaceVelocity.x();
info->b[1] += surfaceVelocity.y();
info->b[2] += surfaceVelocity.z();
Expand Down Expand Up @@ -493,7 +505,7 @@ void ContactConstraint::getInformation(ConstraintInfo* info)
info->b[0] += bouncingVelocity;
{
std::lock_guard<std::mutex> lock(gContactSurfaceMotionVelocitiesMutex);
info->b[0] += gContactSurfaceMotionVelocities[this].x();
info->b[0] += getContactSurfaceMotionVelocities()[this].x();
}

// TODO(JS): Initial guess
Expand Down

0 comments on commit 8495a45

Please sign in to comment.