| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
|
|
| #include <cstdio> |
| #include <cstdlib> |
| #include <cstring> |
|
|
| #include <mujoco/mujoco.h> |
|
|
| |
| #if defined(MJ_EGL) |
| #include <EGL/egl.h> |
| #elif defined(MJ_OSMESA) |
| #include <GL/osmesa.h> |
| OSMesaContext ctx; |
| unsigned char buffer[10000000]; |
| #else |
| #include <GLFW/glfw3.h> |
| #endif |
|
|
| #include "array_safety.h" |
| namespace mju = ::mujoco::sample_util; |
|
|
| |
|
|
| |
| mjModel* m = 0; |
| mjData* d = 0; |
|
|
| |
| mjvScene scn; |
| mjvCamera cam; |
| mjvOption opt; |
| mjrContext con; |
|
|
|
|
| |
|
|
| |
| void initMuJoCo(const char* filename) { |
| |
| char error[1000] = "Could not load binary model"; |
| if (std::strlen(filename)>4 && !std::strcmp(filename+std::strlen(filename)-4, ".mjb")) { |
| m = mj_loadModel(filename, 0); |
| } else { |
| m = mj_loadXML(filename, 0, error, 1000); |
| } |
| if (!m) { |
| mju_error("Load model error: %s", error); |
| } |
|
|
| |
| d = mj_makeData(m); |
| mj_forward(m, d); |
|
|
| |
| mjv_defaultCamera(&cam); |
| mjv_defaultOption(&opt); |
| mjv_defaultScene(&scn); |
| mjr_defaultContext(&con); |
|
|
| |
| mjv_makeScene(m, &scn, 2000); |
| mjr_makeContext(m, &con, 200); |
|
|
| |
| mjv_defaultFreeCamera(m, &cam); |
| } |
|
|
|
|
| |
| void closeMuJoCo(void) { |
| mj_deleteData(d); |
| mj_deleteModel(m); |
| mjr_freeContext(&con); |
| mjv_freeScene(&scn); |
| } |
|
|
|
|
| |
| void initOpenGL(void) { |
| |
| #if defined(MJ_EGL) |
| |
| const EGLint configAttribs[] = { |
| EGL_RED_SIZE, 8, |
| EGL_GREEN_SIZE, 8, |
| EGL_BLUE_SIZE, 8, |
| EGL_ALPHA_SIZE, 8, |
| EGL_DEPTH_SIZE, 24, |
| EGL_STENCIL_SIZE, 8, |
| EGL_COLOR_BUFFER_TYPE, EGL_RGB_BUFFER, |
| EGL_SURFACE_TYPE, EGL_PBUFFER_BIT, |
| EGL_RENDERABLE_TYPE, EGL_OPENGL_BIT, |
| EGL_NONE |
| }; |
|
|
| |
| EGLDisplay eglDpy = eglGetDisplay(EGL_DEFAULT_DISPLAY); |
| if (eglDpy==EGL_NO_DISPLAY) { |
| mju_error("Could not get EGL display, error 0x%x\n", eglGetError()); |
| } |
|
|
| |
| EGLint major, minor; |
| if (eglInitialize(eglDpy, &major, &minor)!=EGL_TRUE) { |
| mju_error("Could not initialize EGL, error 0x%x\n", eglGetError()); |
| } |
|
|
| |
| EGLint numConfigs; |
| EGLConfig eglCfg; |
| if (eglChooseConfig(eglDpy, configAttribs, &eglCfg, 1, &numConfigs)!=EGL_TRUE) { |
| mju_error("Could not choose EGL config, error 0x%x\n", eglGetError()); |
| } |
|
|
| |
| if (eglBindAPI(EGL_OPENGL_API)!=EGL_TRUE) { |
| mju_error("Could not bind EGL OpenGL API, error 0x%x\n", eglGetError()); |
| } |
|
|
| |
| EGLContext eglCtx = eglCreateContext(eglDpy, eglCfg, EGL_NO_CONTEXT, NULL); |
| if (eglCtx==EGL_NO_CONTEXT) { |
| mju_error("Could not create EGL context, error 0x%x\n", eglGetError()); |
| } |
|
|
| |
| if (eglMakeCurrent(eglDpy, EGL_NO_SURFACE, EGL_NO_SURFACE, eglCtx)!=EGL_TRUE) { |
| mju_error("Could not make EGL context current, error 0x%x\n", eglGetError()); |
| } |
|
|
| |
| #elif defined(MJ_OSMESA) |
| |
| ctx = OSMesaCreateContextExt(GL_RGBA, 24, 8, 8, 0); |
| if (!ctx) { |
| mju_error("OSMesa context creation failed"); |
| } |
|
|
| |
| if (!OSMesaMakeCurrent(ctx, buffer, GL_UNSIGNED_BYTE, 800, 800)) { |
| mju_error("OSMesa make current failed"); |
| } |
|
|
| |
| #else |
| |
| if (!glfwInit()) { |
| mju_error("Could not initialize GLFW"); |
| } |
|
|
| |
| glfwWindowHint(GLFW_VISIBLE, 0); |
| glfwWindowHint(GLFW_DOUBLEBUFFER, GLFW_FALSE); |
| GLFWwindow* window = glfwCreateWindow(800, 800, "Invisible window", NULL, NULL); |
| if (!window) { |
| mju_error("Could not create GLFW window"); |
| } |
|
|
| |
| glfwMakeContextCurrent(window); |
| #endif |
| } |
|
|
|
|
| |
| void closeOpenGL(void) { |
| |
| #if defined(MJ_EGL) |
| |
| EGLDisplay eglDpy = eglGetCurrentDisplay(); |
| if (eglDpy==EGL_NO_DISPLAY) { |
| return; |
| } |
|
|
| |
| EGLContext eglCtx = eglGetCurrentContext(); |
|
|
| |
| eglMakeCurrent(eglDpy, EGL_NO_SURFACE, EGL_NO_SURFACE, EGL_NO_CONTEXT); |
|
|
| |
| if (eglCtx!=EGL_NO_CONTEXT) { |
| eglDestroyContext(eglDpy, eglCtx); |
| } |
|
|
| |
| eglTerminate(eglDpy); |
|
|
| |
| #elif defined(MJ_OSMESA) |
| OSMesaDestroyContext(ctx); |
|
|
| |
| #else |
| |
| #if defined(__APPLE__) || defined(_WIN32) |
| glfwTerminate(); |
| #endif |
| #endif |
| } |
|
|
|
|
| |
|
|
| int main(int argc, const char** argv) { |
| |
| if (argc < 5 || argc > 6) { |
| std::printf(" USAGE: record modelfile duration fps rgbfile [adddepth]\n"); |
| return 0; |
| } |
|
|
| |
| double duration = 10, fps = 30; |
| std::sscanf(argv[2], "%lf", &duration); |
| std::sscanf(argv[3], "%lf", &fps); |
|
|
| |
| initOpenGL(); |
| initMuJoCo(argv[1]); |
|
|
| |
| mjr_setBuffer(mjFB_OFFSCREEN, &con); |
| if (con.currentBuffer!=mjFB_OFFSCREEN) { |
| std::printf("Warning: offscreen rendering not supported, using default/window framebuffer\n"); |
| } |
|
|
| |
| mjrRect viewport = mjr_maxViewport(&con); |
| int W = viewport.width; |
| int H = viewport.height; |
|
|
| |
| unsigned char* rgb = (unsigned char*)std::malloc(3*W*H); |
| float* depth = (float*)std::malloc(sizeof(float)*W*H); |
| if (!rgb || !depth) { |
| mju_error("Could not allocate buffers"); |
| } |
|
|
| |
| std::FILE* fp = std::fopen(argv[4], "wb"); |
| if (!fp) { |
| mju_error("Could not open rgbfile for writing"); |
| } |
|
|
| int adddepth = 1; |
| if (argc > 5 && std::sscanf(argv[5], "%d", &adddepth) != 1) { |
| mju_error("Invalid adddepth argument"); |
| } |
|
|
| |
| double frametime = 0; |
| int framecount = 0; |
| while (d->time<duration) { |
| |
| if ((d->time-frametime)>1/fps || frametime==0) { |
| |
| mjv_updateScene(m, d, &opt, NULL, &cam, mjCAT_ALL, &scn); |
|
|
| |
| mjr_render(viewport, &scn, &con); |
|
|
| |
| char stamp[50]; |
| mju::sprintf_arr(stamp, "Time = %.3f", d->time); |
| mjr_overlay(mjFONT_NORMAL, mjGRID_TOPLEFT, viewport, stamp, NULL, &con); |
|
|
| |
| mjr_readPixels(rgb, depth, viewport, &con); |
|
|
| |
| if (adddepth) { |
| const int NS = 3; |
| for (int r=0; r<H; r+=NS) { |
| for (int c=0; c<W; c+=NS) { |
| int adr = (r/NS)*W + c/NS; |
| rgb[3*adr] = rgb[3*adr+1] = rgb[3*adr+2] = (unsigned char)((1.0f-depth[r*W+c])*255.0f); |
| } |
| } |
| } |
|
|
| |
| std::fwrite(rgb, 3, W*H, fp); |
|
|
| |
| if (((framecount++)%10)==0) { |
| if (mjr_getError()) { |
| std::printf("x"); |
| } else { |
| std::printf("."); |
| } |
| } |
|
|
| |
| frametime = d->time; |
| } |
|
|
| |
| mj_step(m, d); |
| } |
| std::printf("\n"); |
|
|
| |
| std::fclose(fp); |
| std::free(rgb); |
| std::free(depth); |
|
|
| |
| closeMuJoCo(); |
| closeOpenGL(); |
|
|
| return 1; |
| } |
|
|