Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

GzOdeCollisionDetector: Use static mutex in create method to avoid problems with non-thread-safe ODE functions #675

Merged
merged 2 commits into from
Oct 17, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 8 additions & 0 deletions dartsim/src/GzOdeCollisionDetector.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
*/

#include <memory>
#include <mutex>
#include <unordered_map>
#include <utility>

Expand Down Expand Up @@ -43,6 +44,13 @@ GzOdeCollisionDetector::Registrar<GzOdeCollisionDetector>
/////////////////////////////////////////////////
std::shared_ptr<GzOdeCollisionDetector> GzOdeCollisionDetector::create()
{
// GzOdeCollisionDetector constructor calls the OdeCollisionDetector
// constructor, that calls the non-thread safe dInitODE2(0).
// To mitigate this problem, we use a static mutex to ensure that
// each GzOdeCollisionDetector constructor is called not at the same time.
// See https://github.com/gazebosim/gz-sim/issues/18 for more info.
static std::mutex odeInitMutex;
std::unique_lock<std::mutex> lock(odeInitMutex);
return std::shared_ptr<GzOdeCollisionDetector>(new GzOdeCollisionDetector());
}

Expand Down