Skip to content

Commit

Permalink
Use a static mutex to avoid race condition in ODE
Browse files Browse the repository at this point in the history
  • Loading branch information
azeey committed Feb 28, 2019
1 parent af503d9 commit 914d44a
Showing 1 changed file with 10 additions and 2 deletions.
12 changes: 10 additions & 2 deletions src/systems/physics/Physics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -169,8 +169,13 @@ class ignition::gazebo::systems::PhysicsPrivate

/// \brief Pointer to the underlying ign-physics Engine entity.
public: EnginePtrType engine = nullptr;

public: static std::mutex initMutex;
};

// Initialize static variable
std::mutex PhysicsPrivate::initMutex;

//////////////////////////////////////////////////
Physics::Physics() : System(), dataPtr(std::make_unique<PhysicsPrivate>())
{
Expand Down Expand Up @@ -247,8 +252,11 @@ void PhysicsPrivate::CreatePhysicsEntities(const EntityComponentManager &_ecm)
sdf::World world;
world.SetName(_name->Data());
world.SetGravity(_gravity->Data());
auto worldPtrPhys = this->engine->ConstructWorld(world);
this->entityWorldMap.insert(std::make_pair(_entity, worldPtrPhys));
{
std::lock_guard<std::mutex> lock(PhysicsPrivate::initMutex);
auto worldPtrPhys = this->engine->ConstructWorld(world);
this->entityWorldMap.insert(std::make_pair(_entity, worldPtrPhys));
}

return true;
});
Expand Down

0 comments on commit 914d44a

Please sign in to comment.