| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #include <chrono> |
| | #include <cctype> |
| | #include <cstddef> |
| | #include <cstdio> |
| | #include <cstring> |
| | #include <iostream> |
| |
|
| | #include <mujoco/mujoco.h> |
| |
|
| | |
| | static constexpr char helpstring[] = |
| | "\n Usage: compile infile outfile\n" |
| | " infile can be in mjcf, urdf, mjb format\n" |
| | " outfile can be in mjcf, mjb, txt format, or empty\n\n" |
| | " if infile is mjcf, compilation will be timed twice to measure the impact of caching\n\n" |
| | " Example: compile model.xml [model.mjb]\n"; |
| |
|
| | |
| | mjtNum gettm(void) { |
| | using Clock = std::chrono::steady_clock; |
| | using Seconds = std::chrono::duration<mjtNum>; |
| | static const Clock::time_point tm_start = Clock::now(); |
| | return Seconds(Clock::now() - tm_start).count(); |
| | } |
| |
|
| | |
| | int finish(const char* msg = 0, mjModel* m = 0) { |
| | |
| | if (m) { |
| | mj_deleteModel(m); |
| | } |
| |
|
| | |
| | if (msg) { |
| | std::cout << msg << std::endl; |
| | } |
| |
|
| | return 0; |
| | } |
| |
|
| |
|
| | |
| | enum { |
| | typeUNKNOWN = 0, |
| | typeXML, |
| | typeMJB, |
| | typeTXT, |
| | typeNONE |
| | }; |
| |
|
| |
|
| | |
| | int filetype(const char* filename) { |
| | |
| | char lower[1000]; |
| | std::size_t i=0; |
| | while (i<std::strlen(filename) && i<999) { |
| | lower[i] = (char)tolower(filename[i]); |
| | i++; |
| | } |
| | lower[i] = 0; |
| |
|
| | |
| | int dot = (int)std::strlen(lower); |
| | while (dot>=0 && lower[dot]!='.') { |
| | dot--; |
| | } |
| |
|
| | |
| | if (dot<0) { |
| | return typeUNKNOWN; |
| | } |
| |
|
| | |
| | if (!std::strcmp(lower+dot, ".xml") || !std::strcmp(lower+dot, ".urdf")) { |
| | return typeXML; |
| | } else if (!std::strcmp(lower+dot, ".mjb")) { |
| | return typeMJB; |
| | } else if (!std::strcmp(lower+dot, ".txt")) { |
| | return typeTXT; |
| | } else { |
| | return typeUNKNOWN; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | int main(int argc, char** argv) { |
| |
|
| | |
| | mjModel* m = 0; |
| | char error[1000]; |
| |
|
| | |
| | if (argc!=3 && argc!=2) { |
| | return finish(helpstring); |
| | } |
| |
|
| | |
| | int type1 = filetype(argv[1]); |
| | int type2 = argc==2 ? typeNONE : filetype(argv[2]); |
| |
|
| | |
| | if (type1==typeUNKNOWN || type1==typeTXT || |
| | type2==typeUNKNOWN || (type1==typeMJB && type2==typeXML)) { |
| | return finish("Illegal combination of file formats"); |
| | } |
| |
|
| | |
| | std::FILE* fp = std::fopen(argv[2], "r"); |
| | if (fp) { |
| | std::cout << "Output file already exists, overwrite? (Y/n) "; |
| | char c; |
| | std::cin >> c; |
| | if (c!='y' && c!='Y') { |
| | std::fclose(fp); |
| | return finish(); |
| | } |
| | } |
| |
|
| | |
| | double first=0, second=0; |
| | if (type1==typeXML) { |
| | double starttime = gettm(); |
| | m = mj_loadXML(argv[1], 0, error, 1000); |
| | first = gettm() - starttime; |
| | if (m) { |
| | mj_deleteModel(m); |
| | starttime = gettm(); |
| | m = mj_loadXML(argv[1], 0, error, 1000); |
| | second = gettm() - starttime; |
| | } |
| | } else { |
| | m = mj_loadModel(argv[1], 0); |
| | } |
| |
|
| | |
| | if (!m) { |
| | if (type1==typeXML) { |
| | return finish(error, 0); |
| | } else { |
| | return finish("Could not load model", 0); |
| | } |
| | } |
| |
|
| | |
| | if (type2==typeXML) { |
| | if (!mj_saveLastXML(argv[2], m, error, 1000)) { |
| | return finish(error, m); |
| | } |
| | } else if (type2==typeMJB) { |
| | mj_saveModel(m, argv[2], 0, 0); |
| | } else if (type2==typeTXT) { |
| | mj_printModel(m, argv[2]); |
| | } |
| |
|
| | |
| | char msg[1000]; |
| | if (first) { |
| | snprintf(msg, sizeof(msg), "Done.\n" |
| | "First compile: %.4gs\n" |
| | "Second compile: %.4gs", |
| | first, second); |
| | } else { |
| | snprintf(msg, sizeof(msg), "Done."); |
| | } |
| |
|
| | return finish(msg, m); |
| | } |
| |
|