Skip to content

Commit 8c7c39a

Browse files
quaglacopybara-github
authored andcommitted
Lock the sim mutex in PhysicsLoop and PhysicsThread.
This prevents an invalid memory access when the stack is used in engine_vis. Fixes #1219. PiperOrigin-RevId: 588017796 Change-Id: I1ee18c5aa5e96ccaeebb0a467cd384355882b80b
1 parent c062a8d commit 8c7c39a

File tree

1 file changed

+16
-1
lines changed

1 file changed

+16
-1
lines changed

simulate/main.cc

Lines changed: 16 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -267,6 +267,9 @@ void PhysicsLoop(mj::Simulate& sim) {
267267
if (dnew) {
268268
sim.Load(mnew, dnew, sim.dropfilename);
269269

270+
// lock the sim mutex
271+
const std::unique_lock<std::recursive_mutex> lock(sim.mtx);
272+
270273
mj_deleteData(d);
271274
mj_deleteModel(m);
272275

@@ -292,6 +295,9 @@ void PhysicsLoop(mj::Simulate& sim) {
292295
if (dnew) {
293296
sim.Load(mnew, dnew, sim.filename);
294297

298+
// lock the sim mutex
299+
const std::unique_lock<std::recursive_mutex> lock(sim.mtx);
300+
295301
mj_deleteData(d);
296302
mj_deleteModel(m);
297303

@@ -421,9 +427,18 @@ void PhysicsThread(mj::Simulate* sim, const char* filename) {
421427
if (filename != nullptr) {
422428
sim->LoadMessage(filename);
423429
m = LoadModel(filename, *sim);
424-
if (m) d = mj_makeData(m);
430+
if (m) {
431+
// lock the sim mutex
432+
const std::unique_lock<std::recursive_mutex> lock(sim->mtx);
433+
434+
d = mj_makeData(m);
435+
}
425436
if (d) {
426437
sim->Load(m, d, filename);
438+
439+
// lock the sim mutex
440+
const std::unique_lock<std::recursive_mutex> lock(sim->mtx);
441+
427442
mj_forward(m, d);
428443

429444
// allocate ctrlnoise

0 commit comments

Comments
 (0)