google-deepmind / mujoco

Multi-Joint dynamics with Contact. A general purpose physics simulator.
https://mujoco.org
Apache License 2.0
8.06k stars 805 forks source link

Rendering to offscreen buffer not working #517

Closed ThoenigAdrian closed 1 year ago

ThoenigAdrian commented 2 years ago

Hi,

I am trying to get offscreen rendering to work.

  1. I create a window
  2. I split the area in half(left and right) by creating two viewports.
  3. I set the buffer to the onscreen window via mjr_setBuffer(mjFB_WINDOW, &con);
  4. I render to the left viewport via mjr_render()
  5. I set the buffer to offscreen via mjr_setBuffer(mjFB_OFFSCREEN, &con);
  6. I get the offscreen buffer viewport
  7. I render to it
  8. I transfer it to the onscreen buffer via mjr_blitBuffer(viewport, dstviewport, 0, 0, &con); and use the viewport for the right half
  9. I display it via glfwSwapBuffer(window)
    mjrRect viewport_left = { 0,0,800,900 };
    mjrRect viewport_right = { 800,0,800,900 };

    std::cout << "Starting rendering..." << std::endl;
    while (!glfwWindowShouldClose(window))
    {

        mjr_setBuffer(mjFB_WINDOW, &con);
        mjv_updateScene(m, d, &opt, NULL, &cam, mjCAT_ALL, &scn);
        mjr_render(viewport_left, &scn, &con);
        mj_step(m, d);
        render_offscreen_then_transfer(viewport_right);     
                glfwSwapBuffers(window);

        // process pending GUI events, call GLFW callbacks
        glfwPollEvents();

    }.......................

void render_offscreen_then_transfer(mjrRect dstviewport)
{
    mjr_setBuffer(mjFB_OFFSCREEN, &con);
    if (con.currentBuffer != mjFB_OFFSCREEN) {
        std::printf("Warning: offscreen rendering not supported, using default/window framebuffer\n");
    }

    // get size of active renderbuffer
    mjrRect viewport = mjr_maxViewport(&con);
    int W = viewport.width;
    int H = viewport.height;
    mjv_updateScene(m, d, &opt, NULL, &cam, mjCAT_ALL, &scn);
    mjr_render(viewport, &scn, &con);
    mjr_blitBuffer(viewport, dstviewport, 0, 0, &con);
}

Actual Behaviour All the pixels which have been transfered from the offscreen buffer are black. image

Expected Behaviour

I would expect the same image to be rendered twice. On the left the one I rendered to the onscreen buffer directly. And on the right the same image which was first rendered to the offscreen and then transferred to the onscreen buffer.

Full code

// Standard libraries
#include <iostream>
#include <string.h>

// Mujuco 
#include "mujoco.h"
#include "glfw3.h"

// MuJoCo data structures
mjModel* m = NULL;                  // MuJoCo model
mjvCamera cam;                      // abstract camera
mjvOption opt;                      // visualization options
mjvScene scn;                       // abstract scene
mjrContext con;                     // custom GPU context
mjData *d;

// UI Dimensions
const int window_width_in_pixel = 1600;
const int window_height_in_pixel = 900;

void load_model(int argc, const char ** argv, mjModel* &model)
{

    // load and compile model
    char error[1000] = "Could not load binary model";

    std::string full_path = "D:\\Software\\mujoco210-windows-x86_64\\mujoco210\\model\\humanoid.xml";
    model = mj_loadXML(full_path.c_str(), 0, error, 1000);

    if (!model)
        mju_error_s("Load model error: %s", error);

}

void render_offscreen_then_transfer(mjrRect dstviewport)
{
    mjr_setBuffer(mjFB_OFFSCREEN, &con);
    if (con.currentBuffer != mjFB_OFFSCREEN) {
        std::printf("Warning: offscreen rendering not supported, using default/window framebuffer\n");
    }

    // get size of active renderbuffer
    mjrRect viewport = mjr_maxViewport(&con);
    int W = viewport.width;
    int H = viewport.height;
    mjv_updateScene(m, d, &opt, NULL, &cam, mjCAT_ALL, &scn);
    mjr_render(viewport, &scn, &con);
    mjr_blitBuffer(viewport, dstviewport, 0, 0, &con);
}

int main(int argc, const char** argv)
{

    load_model(argc, argv, m);

    d = mj_makeData(m);
    mj_resetData(m, d);
    mj_forward(m, d);

    // init GLFW
    if (!glfwInit())
        mju_error("Could not initialize GLFW");

    // create window, make OpenGL context current, request v-sync
    GLFWwindow* window = glfwCreateWindow(window_width_in_pixel, window_height_in_pixel, "Multi Ant", NULL, NULL);
    glfwMakeContextCurrent(window);
    glfwSwapInterval(1);

    // initialize visualization data structures
    mjv_defaultCamera(&cam);
    mjv_defaultOption(&opt);
    mjv_defaultScene(&scn);
    mjr_defaultContext(&con);

    mjv_makeScene(m, &scn, 2000);                // space for 2000 objects
    mjr_makeContext(m, &con, mjFONTSCALE_150);   // model-specific context

                                                 // install GLFW mouse and keyboard callbacks

    mjrRect viewport_left = { 0,0,800,900 };
    mjrRect viewport_right = { 800,0,800,900 };

    std::cout << "Starting rendering..." << std::endl;
    while (!glfwWindowShouldClose(window))
    {

        mjr_setBuffer(mjFB_WINDOW, &con);
        mjv_updateScene(m, d, &opt, NULL, &cam, mjCAT_ALL, &scn);
        mjr_render(viewport_left, &scn, &con);
        mj_step(m, d);
        render_offscreen_then_transfer(viewport_right);

        glfwSwapBuffers(window);

        // process pending GUI events, call GLFW callbacks
        glfwPollEvents();

    }

    std::cout << "UI Window has been closed by the user..." << std::endl;

    std::cout << "Terminating GLFW" << std::endl;
    // terminate GLFW (crashes with Linux NVidia drivers)
#if defined(__APPLE__) || defined(_WIN32)
    glfwTerminate();
#endif
    std::cout << "Freeing mujoco visualization data structures..." << std::endl;
    mjv_freeScene(&scn);
    mjr_freeContext(&con);

    std::cout << "Free MuJoCo model and data, deactivate..." << std::endl;
    mj_deleteModel(m);
    mj_deactivate();
    std::cout << "Shutdown complete..." << std::endl;
    getchar();

    return 0;

}

Additional things i've tried

1.

I also tried writing directly to the offscreen buffer via mjr_drawPixels() since thought maybe there is a issue with mjr_render().

void make_offscreen_buffer_gray(mjrRect dstviewport)
{
    mjr_setBuffer(mjFB_OFFSCREEN, &con);
    if (con.currentBuffer != mjFB_OFFSCREEN) {
        std::printf("Warning: offscreen rendering not supported, using default/window framebuffer\n");
    }

    // get size of active renderbuffer
    mjrRect viewport = mjr_maxViewport(&con);
    int W = viewport.width;
    int H = viewport.height;
    unsigned char *rgb = (unsigned char*)malloc(W*H * 3);
    float *depth = (float*)malloc(W*H * sizeof(float));
    memset(rgb, 127, W*H * 3);
    memset(depth, 0, W*H * sizeof(float));
    mjr_drawPixels(rgb, depth, viewport, &con);
    mjr_blitBuffer(viewport, dstviewport, 0, 0, &con);
}
  1. I thought maybe mjr_blitBuffer() isn't working however it seems even when i use mjr_readPixels() everything is black.

Use case

In case you are wondering why I am trying to do this. I know the above example seems useless however it's just a minimal reproducible example. I have a mujoco scene with multiple agents, where every agent has cameras and i don't want to display all this camera outputs in the window however i need to render them so the neural networks down the line can use this pixels.

What i think the issue might be

I also tried the record.exe sample . And I can get a properly rendered video out of it. So I guess offscreen rendering isn't completly broken. Maybe it has something to do with how the windows is created. Invisible window vs. Visibile Window. Or mabye related to double buffering ? Anyone an Idea how to solve this ?

saran-t commented 2 years ago

Have you tried changing the offwidth and offheight attributes in your XML?

ThoenigAdrian commented 2 years ago

@saran-t no, not yet what should i change it too ? It's currently set at:

    <visual>
        <map force="0.1" zfar="30"/>
        <rgba haze="0.15 0.25 0.35 1"/>
        <quality shadowsize="2048"/>
        <global offwidth="800" offheight="800"/>
    </visual>

I am using the default humanoid.xml .

As far as i understood it should just be the size of the offscreen buffer in this case it renders to 800 * 800 pixels . But since I use mjrRect viewport = mjr_maxViewport(&con); . The mjr_render should always use the exact dimensions for the offscreen buffer. And since blitBuffer should do the scaling according to the documentation it should be fine.

Blit transfers pixels between the two buffers on the GPU and is therefore much faster. The direction is from the active buffer to the buffer that is not active. Note that mjr_blitBuffer has source and destination viewports that can have different size, allowing the image to be scaled in the process.

ThoenigAdrian commented 1 year ago

Found the issue.

mjr_blitBuffer(viewport, dstviewport, 0, 0, &con); vs. mjr_blitBuffer(viewport, viewport_right, 1, 0, &con);

so flg_color needs to be "1" . Since this decides whether the color buffer is copied.

To be honestly I completly misinterpreted the options of mjr_blitBuffer.

If src, dst have different size and flg_depth==0, color is interpolated with GL_LINEAR.

When I read this line I thought this flags refer to some advanced options related to openGL (GL_LINEAR or GL_NEAREST). However this flags are crucial and are basically boolean options which specify whether to blit the depth buffer and/or the color buffer of the Framebuffer object.

In hindsight it might be obvious. Still I think documentation could be improved there to explicitly mention it, just in case.

relevant source code which made me realise my mistake:

void mjr_blitBuffer(mjrRect src, mjrRect dst,
                    int flg_color, int flg_depth, const mjrContext* con) {
  // construct mask and filter for blit
  GLbitfield mask = (flg_color ? GL_COLOR_BUFFER_BIT : 0) |
                    (flg_depth ? GL_DEPTH_BUFFER_BIT : 0);