/
record.cc
325 lines (266 loc) · 8.43 KB
/
record.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
// Copyright 2021 DeepMind Technologies Limited
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <cstdio>
#include <cstdlib>
#include <cstring>
#include <mujoco/mujoco.h>
// select EGL, OSMESA or GLFW
#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;
//-------------------------------- global data ------------------------------------------
// MuJoCo model and data
mjModel* m = 0;
mjData* d = 0;
// MuJoCo visualization
mjvScene scn;
mjvCamera cam;
mjvOption opt;
mjrContext con;
//-------------------------------- utility functions ------------------------------------
// load model, init simulation and rendering
void initMuJoCo(const char* filename) {
// load and compile
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);
}
// make data, run one computation to initialize all fields
d = mj_makeData(m);
mj_forward(m, d);
// initialize visualization data structures
mjv_defaultCamera(&cam);
mjv_defaultOption(&opt);
mjv_defaultScene(&scn);
mjr_defaultContext(&con);
// create scene and context
mjv_makeScene(m, &scn, 2000);
mjr_makeContext(m, &con, 200);
// default free camera
mjv_defaultFreeCamera(m, &cam);
}
// deallocate everything
void closeMuJoCo(void) {
mj_deleteData(d);
mj_deleteModel(m);
mjr_freeContext(&con);
mjv_freeScene(&scn);
}
// create OpenGL context/window
void initOpenGL(void) {
//------------------------ EGL
#if defined(MJ_EGL)
// desired config
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
};
// get default display
EGLDisplay eglDpy = eglGetDisplay(EGL_DEFAULT_DISPLAY);
if (eglDpy==EGL_NO_DISPLAY) {
mju_error("Could not get EGL display, error 0x%x\n", eglGetError());
}
// initialize
EGLint major, minor;
if (eglInitialize(eglDpy, &major, &minor)!=EGL_TRUE) {
mju_error("Could not initialize EGL, error 0x%x\n", eglGetError());
}
// choose config
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());
}
// bind OpenGL API
if (eglBindAPI(EGL_OPENGL_API)!=EGL_TRUE) {
mju_error("Could not bind EGL OpenGL API, error 0x%x\n", eglGetError());
}
// create context
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());
}
// make context current, no surface (let OpenGL handle FBO)
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());
}
//------------------------ OSMESA
#elif defined(MJ_OSMESA)
// create context
ctx = OSMesaCreateContextExt(GL_RGBA, 24, 8, 8, 0);
if (!ctx) {
mju_error("OSMesa context creation failed");
}
// make current
if (!OSMesaMakeCurrent(ctx, buffer, GL_UNSIGNED_BYTE, 800, 800)) {
mju_error("OSMesa make current failed");
}
//------------------------ GLFW
#else
// init GLFW
if (!glfwInit()) {
mju_error("Could not initialize GLFW");
}
// create invisible window, single-buffered
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");
}
// make context current
glfwMakeContextCurrent(window);
#endif
}
// close OpenGL context/window
void closeOpenGL(void) {
//------------------------ EGL
#if defined(MJ_EGL)
// get current display
EGLDisplay eglDpy = eglGetCurrentDisplay();
if (eglDpy==EGL_NO_DISPLAY) {
return;
}
// get current context
EGLContext eglCtx = eglGetCurrentContext();
// release context
eglMakeCurrent(eglDpy, EGL_NO_SURFACE, EGL_NO_SURFACE, EGL_NO_CONTEXT);
// destroy context if valid
if (eglCtx!=EGL_NO_CONTEXT) {
eglDestroyContext(eglDpy, eglCtx);
}
// terminate display
eglTerminate(eglDpy);
//------------------------ OSMESA
#elif defined(MJ_OSMESA)
OSMesaDestroyContext(ctx);
//------------------------ GLFW
#else
// terminate GLFW (crashes with Linux NVidia drivers)
#if defined(__APPLE__) || defined(_WIN32)
glfwTerminate();
#endif
#endif
}
//-------------------------------- main function ----------------------------------------
int main(int argc, const char** argv) {
// check command-line arguments
if (argc < 5 || argc > 6) {
std::printf(" USAGE: record modelfile duration fps rgbfile [adddepth]\n");
return 0;
}
// parse numeric arguments
double duration = 10, fps = 30;
std::sscanf(argv[2], "%lf", &duration);
std::sscanf(argv[3], "%lf", &fps);
// initialize OpenGL and MuJoCo
initOpenGL();
initMuJoCo(argv[1]);
// set rendering to offscreen buffer
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;
// allocate rgb and depth buffers
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");
}
// create output rgb file
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");
}
// main loop
double frametime = 0;
int framecount = 0;
while (d->time<duration) {
// render new frame if it is time (or first frame)
if ((d->time-frametime)>1/fps || frametime==0) {
// update abstract scene
mjv_updateScene(m, d, &opt, NULL, &cam, mjCAT_ALL, &scn);
// render scene in offscreen buffer
mjr_render(viewport, &scn, &con);
// add time stamp in upper-left corner
char stamp[50];
mju::sprintf_arr(stamp, "Time = %.3f", d->time);
mjr_overlay(mjFONT_NORMAL, mjGRID_TOPLEFT, viewport, stamp, NULL, &con);
// read rgb and depth buffers
mjr_readPixels(rgb, depth, viewport, &con);
// insert subsampled depth image in lower-left corner of rgb image
if (adddepth) {
const int NS = 3; // depth image sub-sampling
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);
}
}
}
// write rgb image to file
std::fwrite(rgb, 3, W*H, fp);
// print every 10 frames: '.' if ok, 'x' if OpenGL error
if (((framecount++)%10)==0) {
if (mjr_getError()) {
std::printf("x");
} else {
std::printf(".");
}
}
// save simulation time
frametime = d->time;
}
// advance simulation
mj_step(m, d);
}
std::printf("\n");
// close file, free buffers
std::fclose(fp);
std::free(rgb);
std::free(depth);
// close MuJoCo and OpenGL
closeMuJoCo();
closeOpenGL();
return 1;
}