| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #include "xml/xml_api.h" |
| |
|
| | #include <array> |
| | #include <cstdio> |
| | #include <cstring> |
| | #include <fstream> |
| | #include <functional> |
| | #include <memory> |
| | #include <mutex> |
| | #include <optional> |
| | #include <sstream> |
| | #include <string> |
| | #include <type_traits> |
| |
|
| | #include <mujoco/mjmodel.h> |
| | #include "engine/engine_io.h" |
| | #include <mujoco/mjspec.h> |
| | #include "user/user_resource.h" |
| | #include "user/user_vfs.h" |
| | #include "xml/xml.h" |
| | #include "xml/xml_native_reader.h" |
| | #include "xml/xml_util.h" |
| | #if defined(mjUSEUSD) |
| | #include <mujoco/experimental/usd/usd.h> |
| | #include <pxr/usd/usd/stage.h> |
| | #endif |
| |
|
| | |
| |
|
| | namespace { |
| |
|
| | |
| | class GlobalModel { |
| | public: |
| | |
| | void Set(mjSpec* spec = nullptr); |
| |
|
| | |
| | std::optional<std::string> ToXML(const mjModel* m, char* error, |
| | int error_sz); |
| |
|
| | private: |
| | |
| | std::mutex* mutex_ = new std::mutex(); |
| | mjSpec* spec_ = nullptr; |
| | }; |
| |
|
| | std::optional<std::string> GlobalModel::ToXML(const mjModel* m, char* error, |
| | int error_sz) { |
| | std::lock_guard<std::mutex> lock(*mutex_); |
| | if (!spec_) { |
| | mjCopyError(error, "No XML model loaded", error_sz); |
| | return std::nullopt; |
| | } |
| | std::string result = WriteXML(m, spec_, error, error_sz); |
| | if (result.empty()) { |
| | return std::nullopt; |
| | } |
| | return result; |
| | } |
| |
|
| | void GlobalModel::Set(mjSpec* spec) { |
| | std::lock_guard<std::mutex> lock(*mutex_); |
| | if (spec_ != nullptr) { |
| | mj_deleteSpec(spec_); |
| | } |
| | spec_ = spec; |
| | } |
| |
|
| |
|
| | |
| | GlobalModel& GetGlobalModel() { |
| | static GlobalModel global_model; |
| |
|
| | |
| | static_assert(std::is_trivially_destructible_v<decltype(global_model)>); |
| | return global_model; |
| | } |
| |
|
| | } |
| |
|
| | |
| |
|
| | |
| | |
| | |
| | mjModel* mj_loadXML(const char* filename, const mjVFS* vfs, |
| | char* error, int error_sz) { |
| |
|
| | |
| | std::unique_ptr<mjSpec, std::function<void(mjSpec*)> > spec( |
| | ParseXML(filename, vfs, error, error_sz), |
| | [](mjSpec* s) { |
| | mj_deleteSpec(s); |
| | }); |
| | if (!spec) { |
| | return nullptr; |
| | } |
| |
|
| | |
| | mjModel* m = mj_compile(spec.get(), vfs); |
| | if (!m) { |
| | mjCopyError(error, mjs_getError(spec.get()), error_sz); |
| | return nullptr; |
| | } |
| |
|
| | |
| | if (mjs_isWarning(spec.get())) { |
| | mjCopyError(error, mjs_getError(spec.get()), error_sz); |
| | } else if (error) { |
| | error[0] = '\0'; |
| | } |
| |
|
| | |
| | GetGlobalModel().Set(spec.release()); |
| | return m; |
| | } |
| |
|
| | #if defined(mjUSEUSD) |
| | |
| | |
| | |
| | mjModel* mj_loadUSD(const char* filename, const mjVFS* vfs, char* error, int error_sz) { |
| | auto stage = pxr::UsdStage::Open(filename); |
| |
|
| | if (stage == nullptr) { |
| | mjCopyError(error, "Failed to load USD stage from file.", error_sz); |
| | return nullptr; |
| | } |
| |
|
| | |
| | std::unique_ptr<mjSpec, std::function<void(mjSpec*)> > spec( |
| | mj_parseUSDStage(stage), |
| | [](mjSpec* s) { |
| | mj_deleteSpec(s); |
| | }); |
| |
|
| | |
| | mjModel* m = mj_compile(spec.get(), vfs); |
| | if (!m) { |
| | mjCopyError(error, mjs_getError(spec.get()), error_sz); |
| | return nullptr; |
| | } |
| |
|
| | GetGlobalModel().Set(spec.release()); |
| | return m; |
| | } |
| | #endif |
| |
|
| | |
| | |
| | |
| | int mj_saveLastXML(const char* filename, const mjModel* m, char* error, int error_sz) { |
| | FILE *fp = stdout; |
| | if (filename != nullptr && filename[0] != '\0') { |
| | fp = fopen(filename, "w"); |
| | if (!fp) { |
| | mjCopyError(error, "File not found", error_sz); |
| | return 0; |
| | } |
| | } |
| |
|
| | auto result = GetGlobalModel().ToXML(m, error, error_sz); |
| | if (result.has_value()) { |
| | fprintf(fp, "%s", result->c_str()); |
| | } |
| |
|
| | if (fp != stdout) { |
| | fclose(fp); |
| | } |
| |
|
| | return result.has_value(); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_freeLastXML(void) { |
| | GetGlobalModel().Set(); |
| | } |
| |
|
| |
|
| |
|
| |
|
| | |
| | int mj_printSchema(const char* filename, char* buffer, int buffer_sz, int flg_html, int flg_pad) { |
| | |
| | mjXReader reader; |
| | std::stringstream str; |
| | reader.PrintSchema(str, flg_html != 0, flg_pad != 0); |
| |
|
| | |
| | if (filename) { |
| | std::ofstream file; |
| | file.open(filename); |
| | file << str.str(); |
| | file.close(); |
| | } |
| |
|
| | |
| | if (buffer && buffer_sz) { |
| | strncpy(buffer, str.str().c_str(), buffer_sz); |
| | buffer[buffer_sz-1] = 0; |
| | } |
| |
|
| | |
| | return str.str().size(); |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjModel* mj_loadModel(const char* filename, const mjVFS* vfs) { |
| | std::array<char, 1024> error; |
| | mjResource* resource = mju_openResource("", filename, vfs, |
| | error.data(), error.size()); |
| | if (resource == nullptr) { |
| | mju_warning("%s", error.data()); |
| | return nullptr; |
| | } |
| |
|
| | const void* buffer = NULL; |
| | int buffer_sz = mju_readResource(resource, &buffer); |
| | if (buffer_sz < 1) { |
| | mju_closeResource(resource); |
| | return nullptr; |
| | } |
| |
|
| | mjModel* m = mj_loadModelBuffer(buffer, buffer_sz); |
| | mju_closeResource(resource); |
| | return m; |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjSpec* mj_parseXML(const char* filename, const mjVFS* vfs, char* error, int error_sz) { |
| | return ParseXML(filename, vfs, error, error_sz); |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjSpec* mj_parseXMLString(const char* xml, const mjVFS* vfs, char* error, int error_sz) { |
| | return ParseSpecFromString(xml, vfs, error, error_sz); |
| | } |
| |
|
| |
|
| |
|
| | |
| | int mj_saveXML(const mjSpec* s, const char* filename, char* error, int error_sz) { |
| | |
| | std::string result = WriteXML(NULL, (mjSpec*)s, error, error_sz); |
| | if (result.empty()) { |
| | return -1; |
| | } |
| |
|
| | std::ofstream file; |
| | file.open(filename); |
| | file << result; |
| | file.close(); |
| | return 0; |
| | } |
| |
|
| |
|
| |
|
| | |
| | |
| | int mj_saveXMLString(const mjSpec* s, char* xml, int xml_sz, char* error, int error_sz) { |
| | std::string result = WriteXML(NULL, (mjSpec*)s, error, error_sz); |
| | if (result.empty()) { |
| | return -1; |
| | } else if (result.size() >= xml_sz) { |
| | std::string error_msg = "Output string too short, should be at least " + |
| | std::to_string(result.size()+1); |
| | mjCopyError(error, error_msg.c_str(), error_sz); |
| | return result.size(); |
| | } |
| |
|
| | result.copy(xml, xml_sz); |
| | xml[result.size()] = 0; |
| | return 0; |
| | } |
| |
|
| |
|