| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #include <cerrno> |
| | #include <chrono> |
| | #include <cstdint> |
| | #include <cstdio> |
| | #include <cstdlib> |
| | #include <cstring> |
| | #include <iostream> |
| | #include <memory> |
| | #include <mutex> |
| | #include <new> |
| | #include <string> |
| | #include <thread> |
| |
|
| | #if defined(mjUSEUSD) |
| | #include <mujoco/experimental/usd/usd.h> |
| | #endif |
| | #include <mujoco/mujoco.h> |
| | #include "glfw_adapter.h" |
| | #include "simulate.h" |
| | #include "array_safety.h" |
| |
|
| | #define MUJOCO_PLUGIN_DIR "mujoco_plugin" |
| |
|
| | extern "C" { |
| | #if defined(_WIN32) || defined(__CYGWIN__) |
| | #include <windows.h> |
| | #else |
| | #if defined(__APPLE__) |
| | #include <mach-o/dyld.h> |
| | #endif |
| | #include <errno.h> |
| | #include <unistd.h> |
| | #endif |
| | } |
| |
|
| | namespace { |
| | namespace mj = ::mujoco; |
| | namespace mju = ::mujoco::sample_util; |
| |
|
| | |
| | const double syncMisalign = 0.1; |
| | const double simRefreshFraction = 0.7; |
| | const int kErrorLength = 1024; |
| |
|
| | |
| | mjModel* m = nullptr; |
| | mjData* d = nullptr; |
| |
|
| | using Seconds = std::chrono::duration<double>; |
| |
|
| |
|
| | |
| |
|
| | |
| | |
| | std::string getExecutableDir() { |
| | #if defined(_WIN32) || defined(__CYGWIN__) |
| | constexpr char kPathSep = '\\'; |
| | std::string realpath = [&]() -> std::string { |
| | std::unique_ptr<char[]> realpath(nullptr); |
| | DWORD buf_size = 128; |
| | bool success = false; |
| | while (!success) { |
| | realpath.reset(new(std::nothrow) char[buf_size]); |
| | if (!realpath) { |
| | std::cerr << "cannot allocate memory to store executable path\n"; |
| | return ""; |
| | } |
| |
|
| | DWORD written = GetModuleFileNameA(nullptr, realpath.get(), buf_size); |
| | if (written < buf_size) { |
| | success = true; |
| | } else if (written == buf_size) { |
| | |
| | buf_size *=2; |
| | } else { |
| | std::cerr << "failed to retrieve executable path: " << GetLastError() << "\n"; |
| | return ""; |
| | } |
| | } |
| | return realpath.get(); |
| | }(); |
| | #else |
| | constexpr char kPathSep = '/'; |
| | #if defined(__APPLE__) |
| | std::unique_ptr<char[]> buf(nullptr); |
| | { |
| | std::uint32_t buf_size = 0; |
| | _NSGetExecutablePath(nullptr, &buf_size); |
| | buf.reset(new char[buf_size]); |
| | if (!buf) { |
| | std::cerr << "cannot allocate memory to store executable path\n"; |
| | return ""; |
| | } |
| | if (_NSGetExecutablePath(buf.get(), &buf_size)) { |
| | std::cerr << "unexpected error from _NSGetExecutablePath\n"; |
| | } |
| | } |
| | const char* path = buf.get(); |
| | #else |
| | const char* path = "/proc/self/exe"; |
| | #endif |
| | std::string realpath = [&]() -> std::string { |
| | std::unique_ptr<char[]> realpath(nullptr); |
| | std::uint32_t buf_size = 128; |
| | bool success = false; |
| | while (!success) { |
| | realpath.reset(new(std::nothrow) char[buf_size]); |
| | if (!realpath) { |
| | std::cerr << "cannot allocate memory to store executable path\n"; |
| | return ""; |
| | } |
| |
|
| | std::size_t written = readlink(path, realpath.get(), buf_size); |
| | if (written < buf_size) { |
| | realpath.get()[written] = '\0'; |
| | success = true; |
| | } else if (written == -1) { |
| | if (errno == EINVAL) { |
| | |
| | return path; |
| | } |
| |
|
| | std::cerr << "error while resolving executable path: " << strerror(errno) << '\n'; |
| | return ""; |
| | } else { |
| | |
| | buf_size *= 2; |
| | } |
| | } |
| | return realpath.get(); |
| | }(); |
| | #endif |
| |
|
| | if (realpath.empty()) { |
| | return ""; |
| | } |
| |
|
| | for (std::size_t i = realpath.size() - 1; i > 0; --i) { |
| | if (realpath.c_str()[i] == kPathSep) { |
| | return realpath.substr(0, i); |
| | } |
| | } |
| |
|
| | |
| | return ""; |
| | } |
| |
|
| |
|
| |
|
| | |
| | void scanPluginLibraries() { |
| | |
| | int nplugin = mjp_pluginCount(); |
| | if (nplugin) { |
| | std::printf("Built-in plugins:\n"); |
| | for (int i = 0; i < nplugin; ++i) { |
| | std::printf(" %s\n", mjp_getPluginAtSlot(i)->name); |
| | } |
| | } |
| |
|
| | |
| | #if defined(_WIN32) || defined(__CYGWIN__) |
| | const std::string sep = "\\"; |
| | #else |
| | const std::string sep = "/"; |
| | #endif |
| |
|
| |
|
| | |
| | |
| | |
| | const std::string executable_dir = getExecutableDir(); |
| | if (executable_dir.empty()) { |
| | return; |
| | } |
| |
|
| | const std::string plugin_dir = getExecutableDir() + sep + MUJOCO_PLUGIN_DIR; |
| | mj_loadAllPluginLibraries( |
| | plugin_dir.c_str(), +[](const char* filename, int first, int count) { |
| | std::printf("Plugins registered by library '%s':\n", filename); |
| | for (int i = first; i < first + count; ++i) { |
| | std::printf(" %s\n", mjp_getPluginAtSlot(i)->name); |
| | } |
| | }); |
| | } |
| |
|
| |
|
| | |
| |
|
| | const char* Diverged(int disableflags, const mjData* d) { |
| | if (disableflags & mjDSBL_AUTORESET) { |
| | for (mjtWarning w : {mjWARN_BADQACC, mjWARN_BADQVEL, mjWARN_BADQPOS}) { |
| | if (d->warning[w].number > 0) { |
| | return mju_warningText(w, d->warning[w].lastinfo); |
| | } |
| | } |
| | } |
| | return nullptr; |
| | } |
| |
|
| | mjModel* LoadModel(const char* file, mj::Simulate& sim) { |
| | |
| | char filename[mj::Simulate::kMaxFilenameLength]; |
| | mju::strcpy_arr(filename, file); |
| |
|
| | |
| | if (!filename[0]) { |
| | return nullptr; |
| | } |
| |
|
| | |
| | char loadError[kErrorLength] = ""; |
| | mjModel* mnew = 0; |
| | auto load_start = mj::Simulate::Clock::now(); |
| |
|
| | std::string filename_str(filename); |
| | std::string extension; |
| | size_t dot_pos = filename_str.rfind('.'); |
| |
|
| | if (dot_pos != std::string::npos && dot_pos < filename_str.length() - 1) { |
| | extension = filename_str.substr(dot_pos); |
| | } |
| |
|
| | if (extension == ".mjb") { |
| | mnew = mj_loadModel(filename, nullptr); |
| | if (!mnew) { |
| | mju::strcpy_arr(loadError, "could not load binary model"); |
| | } |
| | #if defined(mjUSEUSD) |
| | } else if (extension == ".usda" || extension == ".usd" || |
| | extension == ".usdc" || extension == ".usdz" ) { |
| | mnew = mj_loadUSD(filename, nullptr, loadError, kErrorLength); |
| | #endif |
| | } else { |
| | mnew = mj_loadXML(filename, nullptr, loadError, kErrorLength); |
| |
|
| | |
| | if (loadError[0]) { |
| | int error_length = mju::strlen_arr(loadError); |
| | if (loadError[error_length-1] == '\n') { |
| | loadError[error_length-1] = '\0'; |
| | } |
| | } |
| | } |
| | auto load_interval = mj::Simulate::Clock::now() - load_start; |
| | double load_seconds = Seconds(load_interval).count(); |
| |
|
| | if (!mnew) { |
| | std::printf("%s\n", loadError); |
| | mju::strcpy_arr(sim.load_error, loadError); |
| | return nullptr; |
| | } |
| |
|
| | |
| | if (loadError[0]) { |
| | |
| | std::printf("Model compiled, but simulation warning (paused):\n %s\n", loadError); |
| | sim.run = 0; |
| | } |
| |
|
| | |
| | else if (load_seconds > 0.25) { |
| | mju::sprintf_arr(loadError, "Model loaded in %.2g seconds", load_seconds); |
| | } |
| |
|
| | mju::strcpy_arr(sim.load_error, loadError); |
| |
|
| | return mnew; |
| | } |
| |
|
| | |
| | void PhysicsLoop(mj::Simulate& sim) { |
| | |
| | std::chrono::time_point<mj::Simulate::Clock> syncCPU; |
| | mjtNum syncSim = 0; |
| |
|
| | |
| | while (!sim.exitrequest.load()) { |
| | if (sim.droploadrequest.load()) { |
| | sim.LoadMessage(sim.dropfilename); |
| | mjModel* mnew = LoadModel(sim.dropfilename, sim); |
| | sim.droploadrequest.store(false); |
| |
|
| | mjData* dnew = nullptr; |
| | if (mnew) dnew = mj_makeData(mnew); |
| | if (dnew) { |
| | sim.Load(mnew, dnew, sim.dropfilename); |
| |
|
| | |
| | const std::unique_lock<std::recursive_mutex> lock(sim.mtx); |
| |
|
| | mj_deleteData(d); |
| | mj_deleteModel(m); |
| |
|
| | m = mnew; |
| | d = dnew; |
| | mj_forward(m, d); |
| |
|
| | } else { |
| | sim.LoadMessageClear(); |
| | } |
| | } |
| |
|
| | if (sim.uiloadrequest.load()) { |
| | sim.uiloadrequest.fetch_sub(1); |
| | sim.LoadMessage(sim.filename); |
| | mjModel* mnew = LoadModel(sim.filename, sim); |
| | mjData* dnew = nullptr; |
| | if (mnew) dnew = mj_makeData(mnew); |
| | if (dnew) { |
| | sim.Load(mnew, dnew, sim.filename); |
| |
|
| | |
| | const std::unique_lock<std::recursive_mutex> lock(sim.mtx); |
| |
|
| | mj_deleteData(d); |
| | mj_deleteModel(m); |
| |
|
| | m = mnew; |
| | d = dnew; |
| | mj_forward(m, d); |
| |
|
| | } else { |
| | sim.LoadMessageClear(); |
| | } |
| | } |
| |
|
| | |
| | |
| | if (sim.run && sim.busywait) { |
| | std::this_thread::yield(); |
| | } else { |
| | std::this_thread::sleep_for(std::chrono::milliseconds(1)); |
| | } |
| |
|
| | { |
| | |
| | const std::unique_lock<std::recursive_mutex> lock(sim.mtx); |
| |
|
| | |
| | if (m) { |
| | |
| | if (sim.run) { |
| | bool stepped = false; |
| |
|
| | |
| | const auto startCPU = mj::Simulate::Clock::now(); |
| |
|
| | |
| | const auto elapsedCPU = startCPU - syncCPU; |
| | double elapsedSim = d->time - syncSim; |
| |
|
| | |
| | double slowdown = 100 / sim.percentRealTime[sim.real_time_index]; |
| |
|
| | |
| | bool misaligned = |
| | std::abs(Seconds(elapsedCPU).count()/slowdown - elapsedSim) > syncMisalign; |
| |
|
| | |
| | if (elapsedSim < 0 || elapsedCPU.count() < 0 || syncCPU.time_since_epoch().count() == 0 || |
| | misaligned || sim.speed_changed) { |
| | |
| | syncCPU = startCPU; |
| | syncSim = d->time; |
| | sim.speed_changed = false; |
| |
|
| | |
| | mj_step(m, d); |
| | const char* message = Diverged(m->opt.disableflags, d); |
| | if (message) { |
| | sim.run = 0; |
| | mju::strcpy_arr(sim.load_error, message); |
| | } else { |
| | stepped = true; |
| | } |
| | } |
| |
|
| | |
| | else { |
| | bool measured = false; |
| | mjtNum prevSim = d->time; |
| |
|
| | double refreshTime = simRefreshFraction/sim.refresh_rate; |
| |
|
| | |
| | while (Seconds((d->time - syncSim)*slowdown) < mj::Simulate::Clock::now() - syncCPU && |
| | mj::Simulate::Clock::now() - startCPU < Seconds(refreshTime)) { |
| | |
| | if (!measured && elapsedSim) { |
| | sim.measured_slowdown = |
| | std::chrono::duration<double>(elapsedCPU).count() / elapsedSim; |
| | measured = true; |
| | } |
| |
|
| | |
| | sim.InjectNoise(); |
| |
|
| | |
| | mj_step(m, d); |
| | const char* message = Diverged(m->opt.disableflags, d); |
| | if (message) { |
| | sim.run = 0; |
| | mju::strcpy_arr(sim.load_error, message); |
| | } else { |
| | stepped = true; |
| | } |
| |
|
| | |
| | if (d->time < prevSim) { |
| | break; |
| | } |
| | } |
| | } |
| |
|
| | |
| | if (stepped) { |
| | sim.AddToHistory(); |
| | } |
| | } |
| |
|
| | |
| | else { |
| | |
| | mj_forward(m, d); |
| | sim.speed_changed = true; |
| | } |
| | } |
| | } |
| | } |
| | } |
| | } |
| |
|
| | |
| |
|
| | void PhysicsThread(mj::Simulate* sim, const char* filename) { |
| | |
| | if (filename != nullptr) { |
| | sim->LoadMessage(filename); |
| | m = LoadModel(filename, *sim); |
| | if (m) { |
| | |
| | const std::unique_lock<std::recursive_mutex> lock(sim->mtx); |
| |
|
| | d = mj_makeData(m); |
| | } |
| | if (d) { |
| | sim->Load(m, d, filename); |
| |
|
| | |
| | const std::unique_lock<std::recursive_mutex> lock(sim->mtx); |
| |
|
| | mj_forward(m, d); |
| |
|
| | } else { |
| | sim->LoadMessageClear(); |
| | } |
| | } |
| |
|
| | PhysicsLoop(*sim); |
| |
|
| | |
| | mj_deleteData(d); |
| | mj_deleteModel(m); |
| | } |
| |
|
| | |
| |
|
| | |
| | #if defined(__APPLE__) && defined(__AVX__) |
| | extern void DisplayErrorDialogBox(const char* title, const char* msg); |
| | static const char* rosetta_error_msg = nullptr; |
| | __attribute__((used, visibility("default"))) extern "C" void _mj_rosettaError(const char* msg) { |
| | rosetta_error_msg = msg; |
| | } |
| | #endif |
| |
|
| | |
| | int main(int argc, char** argv) { |
| |
|
| | |
| | #if defined(__APPLE__) && defined(__AVX__) |
| | if (rosetta_error_msg) { |
| | DisplayErrorDialogBox("Rosetta 2 is not supported", rosetta_error_msg); |
| | std::exit(1); |
| | } |
| | #endif |
| |
|
| | |
| | std::printf("MuJoCo version %s\n", mj_versionString()); |
| | if (mjVERSION_HEADER!=mj_version()) { |
| | mju_error("Headers and library have different versions"); |
| | } |
| |
|
| | |
| | scanPluginLibraries(); |
| |
|
| | #if defined(mjUSEUSD) |
| | |
| | std::printf("OpenUSD version v%d.%02d\n", PXR_MINOR_VERSION, PXR_PATCH_VERSION); |
| | #endif |
| |
|
| | mjvCamera cam; |
| | mjv_defaultCamera(&cam); |
| |
|
| | mjvOption opt; |
| | mjv_defaultOption(&opt); |
| |
|
| | mjvPerturb pert; |
| | mjv_defaultPerturb(&pert); |
| |
|
| | |
| | auto sim = std::make_unique<mj::Simulate>( |
| | std::make_unique<mj::GlfwAdapter>(), |
| | &cam, &opt, &pert, false |
| | ); |
| |
|
| | const char* filename = nullptr; |
| | if (argc > 1) { |
| | filename = argv[1]; |
| | } |
| |
|
| | |
| | std::thread physicsthreadhandle(&PhysicsThread, sim.get(), filename); |
| |
|
| | |
| | sim->RenderLoop(); |
| | physicsthreadhandle.join(); |
| |
|
| | return 0; |
| | } |
| |
|