How to simultaneously visualize and render offscreen

Discussion in 'Modeling' started by Ethan Brooks, Oct 18, 2017.

  1. I have been working on an application in which I need to simultaneously render onscreen and offscreen. Ideally, I would like to render separate cameras. Currently I have code that renders oncreen and captures the images in an array. How would I need to change it to capture images from one camera whilst rendering another camera onscreen?

    Code:
    #include "mujoco.h"
    #include "stdio.h"
    #include "stdlib.h"
    #include "string.h"
    #include "glfw3.h"
    
    // MuJoCo model and data
    mjModel* m = 0;
    mjData* d = 0;
    
    // MuJoCo visualization
    mjvScene scn;
    mjvCamera cam;
    mjvOption opt;
    mjrContext con;
    
    int main(int argc, const char** argv)
    {
        if( !glfwInit() )
            mju_error("Could not initialize GLFW");
    
        // create visible window, double-buffered
        glfwWindowHint(GLFW_VISIBLE, GLFW_TRUE);
        glfwWindowHint(GLFW_DOUBLEBUFFER, GLFW_TRUE);
        GLFWwindow* window = glfwCreateWindow(800, 800, "Visible window", NULL, NULL);
        if( !window )
            mju_error("Could not create GLFW window");
    
        glfwMakeContextCurrent(window);
        mj_activate("mjkey.txt");
    
        char error[1000] = "Could not load xml model";
        m = mj_loadXML("humanoid.xml", 0, error, 1000);
        if( !m )
            mju_error_s("Load model error: %s", error);
        d = mj_makeData(m);
        mj_forward(m, d);
    
        // initialize MuJoCo visualization
        mjv_makeScene(&scn, 1000);
        mjv_defaultCamera(&cam);
        mjv_defaultOption(&opt);
        mjr_defaultContext(&con);
        mjr_makeContext(m, &con, 200);
    
        // get size of window
        mjrRect window_rect = {0, 0, 0, 0};
        glfwGetFramebufferSize(window, &window_rect.width, &window_rect.height);
        int W = window_rect.width;
        int H = window_rect.height;
    
        // allocate rgb and depth buffers
        unsigned char* rgb = (unsigned char*)malloc(3*W*H);
        if( !rgb )
            mju_error("Could not allocate buffers");
    
        // create output rgb file
        FILE* fp = fopen("rgb.out", "wb");
        if( !fp )
            mju_error("Could not open rgbfile for writing");
    
        // main loop
        for( int i = 0; i < 100; i++) {
          mjv_updateScene(m, d, &opt, NULL, &cam, mjCAT_ALL, &scn);
    
          // write offscreen-rendered pixels to file
          mjr_render(window_rect, &scn, &con);
          mjr_readPixels(rgb, NULL, window_rect, &con);
          fwrite(rgb, 3, W*H, fp);
    
          glfwSwapBuffers(window);
          mj_step(m, d);
        }
    
        fclose(fp);
        free(rgb);
        mj_deleteData(d);
        mj_deleteModel(m);
        mjr_freeContext(&con);
        mjv_freeScene(&scn);
        mj_deactivate();
        return 1;
    }
    
    1. Do I need two GLFWwindows?
    2. I know that GLFW is a state machine. How would I toggle between them? Do I call glfwMakeContextCurrent for each?
    3. Do I need separate mjrContexts for each?
    4. Do I need to call mjr_setBuffer for each?
     

    Attached Files:

  2. Emo Todorov

    Emo Todorov Administrator Staff Member

    You need a single GLFW window and a single mjrContext. The context contains an off-screen buffer with resolution specified in the XML model (under visual/global). In addition, the window has its own buffer maintained by the video driver / OS.

    So here is what you need:

    simulation loop:
    advance simulation
    mjr_setBuffer to OFFSCREEN
    adjust your camera
    mjr_render
    (presumably you want the offscreen pixels, so call mjr_readPixels)
    mjr_setBuffer to WINDOW
    adjust your camera if different
    mjr_render
    glfwSwapBuffers


    The idea is that mjr_setBuffer selects the buffer for all subsequent operations, including rendering and reading/writing pixels. You can also copy pixels between the window and offscreen buffers with mjr_blitBuffer (which is much faster than readPixels followed by drawPixels because it happens on the GPU).
     
  3. Thanks. This is extremely helpful. I will use this as the basis for a pull request to mujoco-py, which does not currently do onscreen and offscreen rendering properly.
     
  4. Ok here is my updated code:

    Code:
    #include "mujoco.h"
    #include "stdio.h"
    #include "stdlib.h"
    #include "string.h"
    #include "glfw3.h"
    
    
    //-------------------------------- global data ------------------------------------------
    
    // MuJoCo model and data
    mjModel* m = 0;
    mjData* d = 0;
    
    // MuJoCo visualization
    mjvScene scn;
    mjvCamera cam;
    mjvOption opt;
    mjrContext con;
    
    
    //-------------------------------- main function ----------------------------------------
    
    int main(int argc, const char** argv)
    {
        if( !glfwInit() )
            mju_error("Could not initialize GLFW");
    
        // create visible window, double-buffered
        glfwWindowHint(GLFW_VISIBLE, GLFW_TRUE);
        glfwWindowHint(GLFW_DOUBLEBUFFER, GLFW_TRUE);
        GLFWwindow* window = glfwCreateWindow(800, 800, "Visible window", NULL, NULL);
        if( !window )
            mju_error("Could not create GLFW window");
    
        glfwMakeContextCurrent(window);
        mj_activate("mjkey.txt");
    
        char error[1000] = "Could not load xml model";
        m = mj_loadXML("humanoid.xml", 0, error, 1000);
        if( !m )
            mju_error_s("Load model error: %s", error);
        d = mj_makeData(m);
        mj_forward(m, d);
    
        // initialize MuJoCo visualization
        mjv_makeScene(&scn, 1000);
        mjv_defaultCamera(&cam);
        mjv_defaultOption(&opt);
        mjr_defaultContext(&con);
        mjr_makeContext(m, &con, 200);
    
        // get size of window
        mjrRect window_rect = {0, 0, 0, 0};
        glfwGetFramebufferSize(window, &window_rect.width, &window_rect.height);
        int W = window_rect.width;
        int H = window_rect.height;
    
        // allocate rgb and depth buffers
        unsigned char* rgb = (unsigned char*)malloc(3*W*H);
        if( !rgb )
            mju_error("Could not allocate buffers");
    
        // create output rgb file
        FILE* fp = fopen("rgb.out", "wb");
        if( !fp )
            mju_error("Could not open rgbfile for writing");
    
        // main loop
        for( int i = 0; i < 50; i++) {
          cam.fixedcamid = 0;
          cam.type = mjCAMERA_FIXED;
          mjv_updateScene(m, d, &opt, NULL, &cam, mjCAT_ALL, &scn);
    
          // write offscreen-rendered pixels to file
          mjr_render(window_rect, &scn, &con);
          mjr_readPixels(rgb, NULL, window_rect, &con);
          fwrite(rgb, 3, W*H, fp);
    
          cam.fixedcamid = -1;
          cam.type = mjCAMERA_FREE;
          mjv_updateScene(m, d, &opt, NULL, &cam, mjCAT_ALL, &scn);
          mjr_render(window_rect, &scn, &con);
    
          glfwSwapBuffers(window);
          mj_step(m, d);
        }
    
        fclose(fp);
        free(rgb);
        mj_deleteData(d);
        mj_deleteModel(m);
        mjr_freeContext(&con);
        mjv_freeScene(&scn);
        mj_deactivate();
        return 1;
    }
    
    So I have two questions:
    1. How exactly would I use mjr_blitBuffer in here?
    2. When I resize the display window, the image does not resize (it gets cut off and leaves regions black). What additional commands are necessary to correct that?

    Thanks.
     
  5. Emo Todorov

    Emo Todorov Administrator Staff Member

    You are not actually rendering to the offscreen buffer. Instead you are rendering to the window buffer twice (which is fine of course, but I thought you wanted to do offscreen rendering). The reason you don't see the two renderings in the window is because the second mj_render clears the results of the first. If you want to do offscreen rendering, here is what you need:

    Before the first mj_render, you need the command:
    mj_setBuffer(mjFB_OFFSCREEN, &con);

    Before the second mj_render, you need the command:
    mj_setBuffer(mjFB_WINDOW, &con);


    As for sizing, the offscreen buffer size is under your control (and does not change with window resizing). The window buffer is maintained by the OS / video driver and changes automatically when the window is resized. To deal with resizing, you should install a GLFW refresh callback, handle events, and render whenever the GLFW frameworks asks you to. See the code sample simulate.cpp.

    As for blit, it copies from the currently selected buffer (via the mj_setBuffer command) to the other buffer.
     
  6. Apologies for resurrecting this old issue, but I am running into a problem with this code. I have introduced mj_setBuffer as you suggested resulting in the following:
    Code:
    #include "mujoco.h"
    #include "stdio.h"
    #include "stdlib.h"
    #include "string.h"
    #include "glfw3.h"
    
    
    //-------------------------------- global data ------------------------------------------
    
    // MuJoCo model and data
    mjModel* m = 0;
    mjData* d = 0;
    
    // MuJoCo visualization
    mjvScene scn;
    mjvCamera cam;
    mjvOption opt;
    mjrContext con;
    
    
    //-------------------------------- main function ----------------------------------------
    
    int main(int argc, const char** argv)
    {
        if( !glfwInit() )
            mju_error("Could not initialize GLFW");
    
        // create visible window, double-buffered
        glfwWindowHint(GLFW_VISIBLE, GLFW_TRUE);
        glfwWindowHint(GLFW_DOUBLEBUFFER, GLFW_TRUE);
        GLFWwindow* window = glfwCreateWindow(800, 800, "Visible window", NULL, NULL);
        if( !window )
            mju_error("Could not create GLFW window");
    
        glfwMakeContextCurrent(window);
        mj_activate("mjkey.txt");
    
        char error[1000] = "Could not load xml model";
        m = mj_loadXML("humanoid.xml", 0, error, 1000);
        if( !m )
            mju_error_s("Load model error: %s", error);
        d = mj_makeData(m);
        mj_forward(m, d);
    
        // initialize MuJoCo visualization
        mjv_makeScene(&scn, 1000);
        mjv_defaultCamera(&cam);
        mjv_defaultOption(&opt);
        mjr_defaultContext(&con);
        mjr_makeContext(m, &con, 200);
    
        // get size of window
        mjrRect window_rect = {0, 0, 0, 0};
        glfwGetFramebufferSize(window, &window_rect.width, &window_rect.height);
        int W = window_rect.width;
        int H = window_rect.height;
    
        // allocate rgb and depth buffers
        unsigned char* rgb = (unsigned char*)malloc(3*W*H);
        if( !rgb )
            mju_error("Could not allocate buffers");
    
        // create output rgb file
        FILE* fp = fopen("rgb.out", "wb");
        if( !fp )
            mju_error("Could not open rgbfile for writing");
    
        // main loop
        for( int i = 0; i < 50; i++) {
          cam.fixedcamid = 0;
          cam.type = mjCAMERA_FIXED;
          mjv_updateScene(m, d, &opt, NULL, &cam, mjCAT_ALL, &scn);
    
          // write offscreen-rendered pixels to file
          mjr_setBuffer(mjFB_OFFSCREEN, &con);
          mjr_render(window_rect, &scn, &con);
          mjr_readPixels(rgb, NULL, window_rect, &con);
          fwrite(rgb, 3, W*H, fp);
    
          cam.fixedcamid = -1;
          cam.type = mjCAMERA_FREE;
          mjv_updateScene(m, d, &opt, NULL, &cam, mjCAT_ALL, &scn);
          mjr_setBuffer(mjFB_WINDOW, &con);
          mjr_render(window_rect, &scn, &con);
    
          glfwSwapBuffers(window);
          mj_step(m, d);
        }
    
        fclose(fp);
        free(rgb);
        mj_deleteData(d);
        mj_deleteModel(m);
        mjr_freeContext(&con);
        mjv_freeScene(&scn);
        mj_deactivate();
        return 0;
    }
    What happens is my computer kind of seizes up. I get the spinning wheel of death. Often I have to terminate the program. What am I doing wrong here?
    Meanwhile, if I comment out the mj_setBuffer functions, I get an image that is cropped. For some reason I cannot attach the image because the forum insists that it is not an image, but you will have to take my word for it.
    Thanks for your continuing help with these issues!