diff --git a/docs/pybullet_quickstartguide.pdf b/docs/pybullet_quickstartguide.pdf index 83a89fb9c..9bcdc3e23 100644 Binary files a/docs/pybullet_quickstartguide.pdf and b/docs/pybullet_quickstartguide.pdf differ diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index a336fee9a..f739bbb1c 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -3234,6 +3234,7 @@ bool PhysicsServerCommandProcessor::processImportedObjects(const char* fileName, m_data->m_saveWorldBodyData.push_back(sd); + syncPhysicsToGraphics2(); return loadOk; } @@ -9228,6 +9229,8 @@ bool PhysicsServerCommandProcessor::processInitPoseCommand(const struct SharedMe } } + syncPhysicsToGraphics2(); + SharedMemoryStatus& serverCmd = serverStatusOut; serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED; @@ -13007,6 +13010,7 @@ void PhysicsServerCommandProcessor::resetSimulation() notification.m_notificationType = SIMULATION_RESET; m_data->m_pluginManager.addNotification(notification); + syncPhysicsToGraphics2(); } diff --git a/examples/pybullet/examples/profileTiming.py b/examples/pybullet/examples/profileTiming.py index 5cb0450b8..0904a8f52 100644 --- a/examples/pybullet/examples/profileTiming.py +++ b/examples/pybullet/examples/profileTiming.py @@ -8,6 +8,7 @@ t = time.time() + 3.1 logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "chrome_about_tracing.json") while (time.time() < t): + p.stepSimulation() p.submitProfileTiming("pythontest") time.sleep(1./240.) p.submitProfileTiming("nested")