Merge branch 'physics_render' of https://github.com/fxia22/gibsonv2 into physics_render
This commit is contained in:
commit
9b9b73a6f5
|
@ -1,3 +1,6 @@
|
|||
[submodule "gibson2/core/render/pybind11"]
|
||||
path = gibson2/core/render/pybind11
|
||||
url = https://github.com/pybind/pybind11.git
|
||||
[submodule "gibson2/core/render/glfw"]
|
||||
path = gibson2/core/render/glfw
|
||||
url = https://github.com/glfw/glfw
|
||||
|
|
|
@ -46,7 +46,7 @@ if __name__ == '__main__':
|
|||
|
||||
while True:
|
||||
with Profiler('Render'):
|
||||
frame = renderer.render(modes=('rgb', 'normal', '3d'))
|
||||
frame = renderer.render(modes=('rgb', 'seg', 'normal', '3d'))
|
||||
cv2.imshow('test', cv2.cvtColor(np.concatenate(frame, axis=1), cv2.COLOR_RGB2BGR))
|
||||
q = cv2.waitKey(1)
|
||||
if q == ord('w'):
|
||||
|
|
|
@ -12,25 +12,39 @@ endif()
|
|||
|
||||
add_subdirectory(pybind11)
|
||||
|
||||
# Find GLFW and OpenVR
|
||||
set(GLFW_DIR glfw)
|
||||
set(GLFW_BUILD_EXAMPLES OFF CACHE INTERNAL "Build the GLFW example programs")
|
||||
set(GLFW_BUILD_TESTS OFF CACHE INTERNAL "Build the GLFW test programs")
|
||||
set(GLFW_BUILD_DOCS OFF CACHE INTERNAL "Build the GLFW documentation")
|
||||
set(GLFW_INSTALL OFF CACHE INTERNAL "Generate installation target")
|
||||
add_subdirectory("${GLFW_DIR}")
|
||||
include_directories("${GLFW_DIR}/include")
|
||||
|
||||
find_package(CUDA REQUIRED)
|
||||
set(CUDA_LIBRARIES PUBLIC ${CUDA_LIBRARIES})
|
||||
|
||||
cuda_add_library(MeshRendererContext MODULE glad/egl.cpp glad/gl.cpp cpp/Mesh_renderer.cpp)
|
||||
add_library(CGLUtils MODULE glad/egl.cpp glad/gl.cpp cpp/cgl_utils.cpp)
|
||||
add_library(tinyobjloader MODULE cpp/tinyobjloader/tiny_obj_loader.cc cpp/tinyobjloader/bindings.cc)
|
||||
add_library(GLFWRendererContext MODULE glad/gl.cpp cpp/glfw_mesh_renderer.cpp)
|
||||
|
||||
if (USE_GLAD)
|
||||
target_link_libraries(MeshRendererContext PRIVATE pybind11::module dl pthread)
|
||||
target_link_libraries(CGLUtils PRIVATE pybind11::module dl pthread)
|
||||
target_link_libraries(GLFWRendererContext PRIVATE pybind11::module dl glfw ${GLFW_LIBRARIES})
|
||||
else ()
|
||||
target_link_libraries(MeshRendererContext PRIVATE pybind11::module dl pthread EGL ${OPENGL_LIBRARIES})
|
||||
target_link_libraries(CGLUtils PRIVATE pybind11::module dl pthread EGL ${OPENGL_LIBRARIES})
|
||||
target_link_libraries(GLFWRendererContext PRIVATE pybind11::module dl glfw ${GLFW_LIBRARIES} ${OPENGL_LIBRARIES})
|
||||
endif()
|
||||
|
||||
target_link_libraries(tinyobjloader PRIVATE pybind11::module)
|
||||
|
||||
set_target_properties(MeshRendererContext PROPERTIES PREFIX "${PYTHON_MODULE_PREFIX}"
|
||||
SUFFIX "${PYTHON_MODULE_EXTENSION}")
|
||||
set_target_properties(GLFWRendererContext PROPERTIES PREFIX "${PYTHON_MODULE_PREFIX}"
|
||||
SUFFIX "${PYTHON_MODULE_EXTENSION}")
|
||||
set_target_properties(CGLUtils PROPERTIES PREFIX "${PYTHON_MODULE_PREFIX}"
|
||||
SUFFIX "${PYTHON_MODULE_EXTENSION}")
|
||||
set_target_properties(tinyobjloader PROPERTIES PREFIX "${PYTHON_MODULE_PREFIX}"
|
||||
|
|
|
@ -6,12 +6,22 @@
|
|||
#include <pybind11/pybind11.h>
|
||||
#include <pybind11/stl.h>
|
||||
#include <pybind11/numpy.h>
|
||||
#define STB_IMAGE_IMPLEMENTATION
|
||||
#include "stb_image.h"
|
||||
|
||||
namespace py = pybind11;
|
||||
|
||||
void render_meshrenderer_pre() {
|
||||
void render_meshrenderer_pre(bool msaa, GLuint fb1, GLuint fb2) {
|
||||
|
||||
glBindFramebuffer(GL_FRAMEBUFFER, fb2);
|
||||
glClearColor(0.0f, 0.0f, 0.0f, 1.0f);
|
||||
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
|
||||
|
||||
if (msaa) {
|
||||
glBindFramebuffer(GL_FRAMEBUFFER, fb1);
|
||||
glClearColor(0.0f, 0.0f, 0.0f, 1.0f);
|
||||
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
|
||||
}
|
||||
glEnable(GL_DEPTH_TEST);
|
||||
}
|
||||
|
||||
|
@ -30,7 +40,20 @@ std::string getstring_meshrenderer() {
|
|||
return reinterpret_cast<char const *>(glGetString(GL_VERSION));
|
||||
}
|
||||
|
||||
py::array_t<float> readbuffer_meshrenderer(char* mode, int width, int height) {
|
||||
void blit_buffer(int width, int height, GLuint fb1, GLuint fb2) {
|
||||
glBindFramebuffer(GL_READ_FRAMEBUFFER, fb1);
|
||||
glBindFramebuffer(GL_DRAW_FRAMEBUFFER, fb2);
|
||||
glBlitFramebuffer(0, 0, width, height, 0, 0, width, height, GL_DEPTH_BUFFER_BIT, GL_NEAREST);
|
||||
|
||||
for (int i = 0; i < 4; i++) {
|
||||
glReadBuffer(GL_COLOR_ATTACHMENT0+i);
|
||||
glDrawBuffer(GL_COLOR_ATTACHMENT0+i);
|
||||
glBlitFramebuffer(0, 0, width, height, 0, 0, width, height, GL_COLOR_BUFFER_BIT, GL_NEAREST);
|
||||
}
|
||||
}
|
||||
|
||||
py::array_t<float> readbuffer_meshrenderer(char* mode, int width, int height, GLuint fb2) {
|
||||
glBindFramebuffer(GL_FRAMEBUFFER, fb2);
|
||||
if (!strcmp(mode, "rgb")) {
|
||||
glReadBuffer(GL_COLOR_ATTACHMENT0);
|
||||
}
|
||||
|
@ -107,6 +130,51 @@ py::list setup_framebuffer_meshrenderer(int width, int height) {
|
|||
return result;
|
||||
}
|
||||
|
||||
py::list setup_framebuffer_meshrenderer_ms(int width, int height) {
|
||||
GLuint *fbo_ptr = (GLuint*)malloc(sizeof(GLuint));
|
||||
GLuint *texture_ptr = (GLuint*)malloc(5 * sizeof(GLuint));
|
||||
glGenFramebuffers(1, fbo_ptr);
|
||||
glGenTextures(5, texture_ptr);
|
||||
int fbo = fbo_ptr[0];
|
||||
int color_tex_rgb = texture_ptr[0];
|
||||
int color_tex_normal = texture_ptr[1];
|
||||
int color_tex_semantics = texture_ptr[2];
|
||||
int color_tex_3d = texture_ptr[3];
|
||||
int depth_tex = texture_ptr[4];
|
||||
glBindTexture(GL_TEXTURE_2D_MULTISAMPLE, color_tex_rgb);
|
||||
glTexImage2DMultisample(GL_TEXTURE_2D_MULTISAMPLE, 4, GL_RGBA, width, height, GL_TRUE);
|
||||
glBindTexture(GL_TEXTURE_2D_MULTISAMPLE, color_tex_normal);
|
||||
glTexImage2DMultisample(GL_TEXTURE_2D_MULTISAMPLE, 4, GL_RGBA, width, height, GL_TRUE);
|
||||
glBindTexture(GL_TEXTURE_2D_MULTISAMPLE, color_tex_semantics);
|
||||
glTexImage2DMultisample(GL_TEXTURE_2D_MULTISAMPLE, 4, GL_RGBA, width, height, GL_TRUE);
|
||||
glBindTexture(GL_TEXTURE_2D_MULTISAMPLE, color_tex_3d);
|
||||
glTexImage2DMultisample(GL_TEXTURE_2D_MULTISAMPLE, 4, GL_RGBA, width, height, GL_TRUE);
|
||||
glBindTexture(GL_TEXTURE_2D_MULTISAMPLE, depth_tex);
|
||||
glTexImage2DMultisample(GL_TEXTURE_2D_MULTISAMPLE, 4, GL_DEPTH24_STENCIL8, width, height, GL_TRUE);
|
||||
glBindFramebuffer(GL_FRAMEBUFFER, fbo);
|
||||
glFramebufferTexture2D(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT0, GL_TEXTURE_2D_MULTISAMPLE, color_tex_rgb, 0);
|
||||
glFramebufferTexture2D(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT1, GL_TEXTURE_2D_MULTISAMPLE, color_tex_normal, 0);
|
||||
glFramebufferTexture2D(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT2, GL_TEXTURE_2D_MULTISAMPLE, color_tex_semantics, 0);
|
||||
glFramebufferTexture2D(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT3, GL_TEXTURE_2D_MULTISAMPLE, color_tex_3d, 0);
|
||||
glFramebufferTexture2D(GL_FRAMEBUFFER, GL_DEPTH_STENCIL_ATTACHMENT, GL_TEXTURE_2D_MULTISAMPLE, depth_tex, 0);
|
||||
glViewport(0, 0, width, height);
|
||||
GLenum *bufs = (GLenum*)malloc(4 * sizeof(GLenum));
|
||||
bufs[0] = GL_COLOR_ATTACHMENT0;
|
||||
bufs[1] = GL_COLOR_ATTACHMENT1;
|
||||
bufs[2] = GL_COLOR_ATTACHMENT2;
|
||||
bufs[3] = GL_COLOR_ATTACHMENT3;
|
||||
glDrawBuffers(4, bufs);
|
||||
assert(glCheckFramebufferStatus(GL_FRAMEBUFFER) == GL_FRAMEBUFFER_COMPLETE);
|
||||
py::list result;
|
||||
result.append(fbo);
|
||||
result.append(color_tex_rgb);
|
||||
result.append(color_tex_normal);
|
||||
result.append(color_tex_semantics);
|
||||
result.append(color_tex_3d);
|
||||
result.append(depth_tex);
|
||||
return result;
|
||||
}
|
||||
|
||||
py::list compile_shader_meshrenderer(char* vertexShaderSource, char* fragmentShaderSource) {
|
||||
int vertexShader = glCreateShader(GL_VERTEX_SHADER);
|
||||
glShaderSource(vertexShader, 1, &vertexShaderSource, NULL);
|
||||
|
@ -206,11 +274,12 @@ void init_material_instance(int shaderProgram, float instance_color, py::array_t
|
|||
glUniform1f(glGetUniformLocation(shaderProgram, "use_texture"), use_texture);
|
||||
}
|
||||
|
||||
void draw_elements_instance(bool flag, int texture_id, int texUnitUniform, int vao, int face_size, py::array_t<unsigned int> faces) {
|
||||
void draw_elements_instance(bool flag, int texture_id, int texUnitUniform, int vao, int face_size, py::array_t<unsigned int> faces, GLuint fb) {
|
||||
glActiveTexture(GL_TEXTURE0);
|
||||
if (flag) glBindTexture(GL_TEXTURE_2D, texture_id);
|
||||
glUniform1i(texUnitUniform, 0);
|
||||
glBindVertexArray(vao);
|
||||
glBindFramebuffer(GL_FRAMEBUFFER, fb);
|
||||
unsigned int *ptr = (unsigned int *) faces.request().ptr;
|
||||
glDrawElements(GL_TRIANGLES, face_size, GL_UNSIGNED_INT, ptr);
|
||||
|
||||
|
@ -239,12 +308,22 @@ void init_material_pos_instance(int shaderProgram, py::array_t<float> pose_trans
|
|||
glUniform1f(glGetUniformLocation(shaderProgram, "use_texture"), use_texture);
|
||||
}
|
||||
|
||||
void render_tensor_pre() {
|
||||
glClearColor(0, 0, 0, 1);
|
||||
|
||||
void render_tensor_pre(bool msaa, GLuint fb1, GLuint fb2) {
|
||||
|
||||
glBindFramebuffer(GL_FRAMEBUFFER, fb2);
|
||||
glClearColor(0.0f, 0.0f, 0.0f, 1.0f);
|
||||
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
|
||||
|
||||
if (msaa) {
|
||||
glBindFramebuffer(GL_FRAMEBUFFER, fb1);
|
||||
glClearColor(0.0f, 0.0f, 0.0f, 1.0f);
|
||||
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
|
||||
}
|
||||
glEnable(GL_DEPTH_TEST);
|
||||
}
|
||||
|
||||
|
||||
void render_tensor_post() {
|
||||
glDisable(GL_DEPTH_TEST);
|
||||
}
|
||||
|
@ -257,6 +336,50 @@ void cglUseProgram(int shaderProgram) {
|
|||
glUseProgram(shaderProgram);
|
||||
}
|
||||
|
||||
int loadTexture(std::string filename) {
|
||||
// img = Image.open(path).transpose(Image.FLIP_TOP_BOTTOM)
|
||||
// w, h = img.size
|
||||
//
|
||||
// img = img.resize((int(w * scale), int(h * scale)), Image.BICUBIC)
|
||||
|
||||
// img_data = np.frombuffer(img.tobytes(), np.uint8)
|
||||
// #print(img_data.shape)
|
||||
//width, height = img.size
|
||||
// glTexImage2D expects the first element of the image data to be the
|
||||
// bottom-left corner of the image. Subsequent elements go left to right,
|
||||
// with subsequent lines going from bottom to top.
|
||||
|
||||
// However, the image data was created with PIL Image tostring and numpy's
|
||||
// fromstring, which means we have to do a bit of reorganization. The first
|
||||
// element in the data output by tostring() will be the top-left corner of
|
||||
// the image, with following values going left-to-right and lines going
|
||||
// top-to-bottom. So, we need to flip the vertical coordinate (y).
|
||||
|
||||
int w;
|
||||
int h;
|
||||
int comp;
|
||||
stbi_set_flip_vertically_on_load(true);
|
||||
unsigned char* image = stbi_load(filename.c_str(), &w, &h, &comp, STBI_rgb);
|
||||
|
||||
if(image == nullptr)
|
||||
throw(std::string("Failed to load texture"));
|
||||
|
||||
|
||||
GLuint texture;
|
||||
glGenTextures(1, &texture);
|
||||
glPixelStorei(GL_UNPACK_ALIGNMENT, 1);
|
||||
glBindTexture(GL_TEXTURE_2D, texture);
|
||||
glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR);
|
||||
glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR_MIPMAP_LINEAR);
|
||||
glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_REPEAT);
|
||||
glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_REPEAT);
|
||||
glTexImage2D(GL_TEXTURE_2D, 0, GL_RGB, w, h, 0, GL_RGB,
|
||||
GL_UNSIGNED_BYTE, image);
|
||||
glGenerateMipmap(GL_TEXTURE_2D);
|
||||
stbi_image_free(image);
|
||||
return texture;
|
||||
}
|
||||
|
||||
PYBIND11_MODULE(CGLUtils, m) {
|
||||
m.doc() = "C++ OpenGL bindings";
|
||||
|
||||
|
@ -268,8 +391,12 @@ PYBIND11_MODULE(CGLUtils, m) {
|
|||
m.def("glad_init", &glad_init, "init glad");
|
||||
m.def("clean_meshrenderer", &clean_meshrenderer, "clean meshrenderer");
|
||||
m.def("setup_framebuffer_meshrenderer", &setup_framebuffer_meshrenderer, "setup framebuffer in meshrenderer");
|
||||
m.def("setup_framebuffer_meshrenderer_ms", &setup_framebuffer_meshrenderer_ms, "setup framebuffer in meshrenderer with MSAA");
|
||||
m.def("blit_buffer", &blit_buffer, "blit buffer");
|
||||
|
||||
m.def("compile_shader_meshrenderer", &compile_shader_meshrenderer, "compile vertex and fragment shader");
|
||||
m.def("load_object_meshrenderer", &load_object_meshrenderer, "load object into VAO and VBO");
|
||||
m.def("loadTexture", &loadTexture, "load texture function");
|
||||
|
||||
// class MeshRendererG2G
|
||||
m.def("render_tensor_pre", &render_tensor_pre, "pre-executed functions in MeshRendererG2G.render");
|
||||
|
@ -288,4 +415,5 @@ PYBIND11_MODULE(CGLUtils, m) {
|
|||
// misc
|
||||
m.def("cglBindVertexArray", &cglBindVertexArray, "binding function");
|
||||
m.def("cglUseProgram", &cglUseProgram, "binding function");
|
||||
|
||||
}
|
|
@ -0,0 +1,76 @@
|
|||
#include <stdio.h>
|
||||
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#define GLFW_INCLUDE_NONE
|
||||
#include <GLFW/glfw3.h>
|
||||
#include <glad/gl.h>
|
||||
|
||||
#include <pybind11/pybind11.h>
|
||||
#include <pybind11/numpy.h>
|
||||
#include <pybind11/stl.h>
|
||||
|
||||
namespace py = pybind11;
|
||||
|
||||
class GLFWRendererContext {
|
||||
public:
|
||||
GLFWRendererContext(int w, int h) :m_windowHeight(h), m_windowWidth(w) {};
|
||||
|
||||
int m_windowWidth;
|
||||
int m_windowHeight;
|
||||
|
||||
int init() {
|
||||
// Initialize GLFW context and window
|
||||
if (!glfwInit()) {
|
||||
fprintf(stderr, "Failed to initialize GLFW.\n");
|
||||
exit(EXIT_FAILURE);
|
||||
}
|
||||
|
||||
glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 3);
|
||||
glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 3);
|
||||
glfwWindowHint(GLFW_OPENGL_PROFILE, GLFW_OPENGL_CORE_PROFILE);
|
||||
|
||||
// Hide GLFW window by default
|
||||
glfwWindowHint(GLFW_VISIBLE, GLFW_FALSE);
|
||||
|
||||
GLFWwindow* window = glfwCreateWindow(m_windowHeight, m_windowHeight, "Gibson VR Renderer", NULL, NULL);
|
||||
if (window == NULL) {
|
||||
fprintf(stderr, "Failed to create GLFW window.\n");
|
||||
exit(EXIT_FAILURE);
|
||||
}
|
||||
glfwMakeContextCurrent(window);
|
||||
|
||||
// Load all OpenGL function pointers through GLAD
|
||||
if (!gladLoadGL(glfwGetProcAddress))
|
||||
{
|
||||
fprintf(stderr, "Failed to load OpenGL function pointers through GLAD.\n");
|
||||
exit(EXIT_FAILURE);
|
||||
}
|
||||
|
||||
printf("Succesfully initialized GLFW context and window!\n");
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void release() {
|
||||
glfwTerminate();
|
||||
}
|
||||
};
|
||||
|
||||
PYBIND11_MODULE(GLFWRendererContext, m) {
|
||||
m.doc() = "C++ GLFW bindings";
|
||||
|
||||
py::class_<GLFWRendererContext>(m, "GLFWRendererContext")
|
||||
.def(py::init<int, int>())
|
||||
.def("init", &GLFWRendererContext::init)
|
||||
.def("release", &GLFWRendererContext::release);
|
||||
|
||||
#ifdef VERSION_INFO
|
||||
m.attr("__version__") = VERSION_INFO;
|
||||
#else
|
||||
m.attr("__version__") = "dev";
|
||||
#endif
|
||||
}
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1 @@
|
|||
Subproject commit 76406c7894912125afae59e6e5be00222ba10b48
|
|
@ -11,7 +11,7 @@ import numpy as np
|
|||
from gibson2.core.render.mesh_renderer.glutils.meshutil import perspective, lookat, xyz2mat, quat2rotmat, mat2xyz, safemat2quat
|
||||
from transforms3d.quaternions import axangle2quat, mat2quat
|
||||
from transforms3d.euler import quat2euler, mat2euler
|
||||
from gibson2.core.render.mesh_renderer import MeshRendererContext, CGLUtils
|
||||
from gibson2.core.render.mesh_renderer import MeshRendererContext, CGLUtils, GLFWRendererContext
|
||||
from gibson2.core.render.mesh_renderer.get_available_devices import get_available_devices
|
||||
from gibson2.core.render.mesh_renderer.glutils.utils import colormap, loadTexture
|
||||
import gibson2.core.render.mesh_renderer as mesh_renderer
|
||||
|
@ -107,7 +107,13 @@ class InstanceGroup(object):
|
|||
texture_id = self.renderer.materials_mapping[self.renderer.mesh_materials[object_idx]].texture_id
|
||||
if texture_id is None:
|
||||
texture_id = -1
|
||||
CGLUtils.draw_elements_instance(self.renderer.materials_mapping[self.renderer.mesh_materials[object_idx]].is_texture(), texture_id, self.renderer.texUnitUniform, self.renderer.VAOs[object_idx], self.renderer.faces[object_idx].size, self.renderer.faces[object_idx])
|
||||
|
||||
if self.renderer.msaa:
|
||||
buffer = self.renderer.fbo_ms
|
||||
else:
|
||||
buffer = self.renderer.fbo
|
||||
|
||||
CGLUtils.draw_elements_instance(self.renderer.materials_mapping[self.renderer.mesh_materials[object_idx]].is_texture(), texture_id, self.renderer.texUnitUniform, self.renderer.VAOs[object_idx], self.renderer.faces[object_idx].size, self.renderer.faces[object_idx], buffer)
|
||||
|
||||
finally:
|
||||
CGLUtils.cglBindVertexArray(0)
|
||||
|
@ -211,7 +217,13 @@ class Instance(object):
|
|||
texture_id = self.renderer.materials_mapping[self.renderer.mesh_materials[object_idx]].texture_id
|
||||
if texture_id is None:
|
||||
texture_id = -1
|
||||
CGLUtils.draw_elements_instance(self.renderer.materials_mapping[self.renderer.mesh_materials[object_idx]].is_texture(), texture_id, self.renderer.texUnitUniform, self.renderer.VAOs[object_idx], self.renderer.faces[object_idx].size, self.renderer.faces[object_idx])
|
||||
|
||||
if self.renderer.msaa:
|
||||
buffer = self.renderer.fbo_ms
|
||||
else:
|
||||
buffer = self.renderer.fbo
|
||||
|
||||
CGLUtils.draw_elements_instance(self.renderer.materials_mapping[self.renderer.mesh_materials[object_idx]].is_texture(), texture_id, self.renderer.texUnitUniform, self.renderer.VAOs[object_idx], self.renderer.faces[object_idx].size, self.renderer.faces[object_idx], buffer)
|
||||
|
||||
finally:
|
||||
CGLUtils.cglBindVertexArray(0)
|
||||
|
@ -258,7 +270,7 @@ class MeshRenderer:
|
|||
MeshRenderer is a lightweight OpenGL renderer. It manages a set of visual objects, and instances of those objects.
|
||||
It also manage a device to create OpenGL context on, and create buffers to store rendering results.
|
||||
"""
|
||||
def __init__(self, width=512, height=512, fov=90, device_idx=0, use_fisheye=False):
|
||||
def __init__(self, width=512, height=512, fov=90, device_idx=0, use_fisheye=False, msaa=False):
|
||||
"""
|
||||
:param width: width of the renderer output
|
||||
:param height: width of the renderer output
|
||||
|
@ -296,6 +308,8 @@ class MeshRenderer:
|
|||
|
||||
self.device_idx = device_idx
|
||||
self.device_minor = device
|
||||
self.msaa = msaa
|
||||
#self.r = GLFWRendererContext.GLFWRendererContext(width, height)
|
||||
self.r = MeshRendererContext.MeshRendererContext(width, height, device)
|
||||
self.r.init()
|
||||
|
||||
|
@ -343,7 +357,12 @@ class MeshRenderer:
|
|||
"""
|
||||
Set up RGB, surface normal, depth and segmentation framebuffers for the renderer
|
||||
"""
|
||||
[self.fbo, self.color_tex_rgb, self.color_tex_normal, self.color_tex_semantics, self.color_tex_3d, self.depth_tex] = CGLUtils.setup_framebuffer_meshrenderer(self.width, self.height)
|
||||
[self.fbo, self.color_tex_rgb, self.color_tex_normal, self.color_tex_semantics, self.color_tex_3d,
|
||||
self.depth_tex] = CGLUtils.setup_framebuffer_meshrenderer(self.width, self.height)
|
||||
|
||||
if self.msaa:
|
||||
[self.fbo_ms, self.color_tex_rgb_ms, self.color_tex_normal_ms, self.color_tex_semantics_ms, self.color_tex_3d_ms,
|
||||
self.depth_tex_ms] = CGLUtils.setup_framebuffer_meshrenderer_ms(self.width, self.height)
|
||||
|
||||
def load_object(self,
|
||||
obj_path,
|
||||
|
@ -404,7 +423,8 @@ class MeshRenderer:
|
|||
if load_texture:
|
||||
materials_fn[i + material_count] = item.diffuse_texname
|
||||
dir = os.path.dirname(obj_path)
|
||||
texture = loadTexture(os.path.join(dir, item.diffuse_texname), scale=texture_scale)
|
||||
#texture = loadTexture(os.path.join(dir, item.diffuse_texname), scale=texture_scale)
|
||||
texture = CGLUtils.loadTexture(os.path.join(dir, item.diffuse_texname))
|
||||
material = Material('texture', texture_id=texture)
|
||||
self.textures.append(texture)
|
||||
else:
|
||||
|
@ -599,22 +619,22 @@ class MeshRenderer:
|
|||
"""
|
||||
results = []
|
||||
if 'rgb' in modes:
|
||||
frame = CGLUtils.readbuffer_meshrenderer('rgb', self.width, self.height)
|
||||
frame = CGLUtils.readbuffer_meshrenderer('rgb', self.width, self.height, self.fbo)
|
||||
frame = frame.reshape(self.height, self.width, 4)[::-1, :]
|
||||
results.append(frame)
|
||||
|
||||
if 'normal' in modes:
|
||||
normal = CGLUtils.readbuffer_meshrenderer('normal', self.width, self.height)
|
||||
normal = CGLUtils.readbuffer_meshrenderer('normal', self.width, self.height, self.fbo)
|
||||
normal = normal.reshape(self.height, self.width, 4)[::-1, :]
|
||||
results.append(normal)
|
||||
|
||||
if 'seg' in modes:
|
||||
seg = CGLUtils.readbuffer_meshrenderer('seg', self.width, self.height)
|
||||
seg = CGLUtils.readbuffer_meshrenderer('seg', self.width, self.height, self.fbo)
|
||||
seg = seg.reshape(self.height, self.width, 4)[::-1, :]
|
||||
results.append(seg)
|
||||
|
||||
if '3d' in modes:
|
||||
pc = CGLUtils.readbuffer_meshrenderer('3d', self.width, self.height)
|
||||
pc = CGLUtils.readbuffer_meshrenderer('3d', self.width, self.height, self.fbo)
|
||||
pc = pc.reshape(self.height, self.width, 4)[::-1, :]
|
||||
results.append(pc)
|
||||
|
||||
|
@ -629,13 +649,18 @@ class MeshRenderer:
|
|||
hidden
|
||||
|
||||
"""
|
||||
CGLUtils.render_meshrenderer_pre()
|
||||
if self.msaa:
|
||||
CGLUtils.render_meshrenderer_pre(1, self.fbo_ms, self.fbo)
|
||||
else:
|
||||
CGLUtils.render_meshrenderer_pre(0, 0, self.fbo)
|
||||
|
||||
for instance in self.instances:
|
||||
if not instance in hidden:
|
||||
instance.render()
|
||||
|
||||
CGLUtils.render_meshrenderer_post()
|
||||
if self.msaa:
|
||||
CGLUtils.blit_buffer(self.width, self.height, self.fbo_ms, self.fbo)
|
||||
|
||||
return self.readbuffer(modes)
|
||||
|
||||
|
@ -665,7 +690,15 @@ class MeshRenderer:
|
|||
self.color_tex_rgb, self.color_tex_normal, self.color_tex_semantics, self.color_tex_3d,
|
||||
self.depth_tex
|
||||
]
|
||||
CGLUtils.clean_meshrenderer(clean_list, self.textures, [self.fbo], self.VAOs, self.VBOs)
|
||||
fbo_list = [self.fbo]
|
||||
if self.msaa:
|
||||
clean_list += [
|
||||
self.color_tex_rgb_ms, self.color_tex_normal_ms, self.color_tex_semantics_ms, self.color_tex_3d_ms,
|
||||
self.depth_tex_ms
|
||||
]
|
||||
fbo_list += [self.fbo_ms]
|
||||
|
||||
CGLUtils.clean_meshrenderer(clean_list, self.textures, fbo_list, self.VAOs, self.VBOs)
|
||||
self.color_tex_rgb = None
|
||||
self.color_tex_normal = None
|
||||
self.color_tex_semantics = None
|
||||
|
|
|
@ -11,8 +11,8 @@ class MeshRendererG2G(MeshRenderer):
|
|||
pytorch installation is required.
|
||||
"""
|
||||
|
||||
def __init__(self, width=512, height=512, fov=90, device_idx=0, use_fisheye=False):
|
||||
super(MeshRendererG2G, self).__init__(width, height, fov, device_idx, use_fisheye)
|
||||
def __init__(self, width=512, height=512, fov=90, device_idx=0, use_fisheye=False, msaa=False):
|
||||
super(MeshRendererG2G, self).__init__(width, height, fov, device_idx, use_fisheye, msaa)
|
||||
self.cuda_idx = get_cuda_device(self.device_minor)
|
||||
print("Using cuda device {}".format(self.cuda_idx))
|
||||
with torch.cuda.device(self.cuda_idx):
|
||||
|
@ -52,12 +52,17 @@ class MeshRendererG2G(MeshRenderer):
|
|||
hidden
|
||||
|
||||
"""
|
||||
CGLUtils.render_tensor_pre()
|
||||
if self.msaa:
|
||||
CGLUtils.render_tensor_pre(1, self.fbo_ms, self.fbo)
|
||||
else:
|
||||
CGLUtils.render_tensor_pre(0, 0, self.fbo)
|
||||
|
||||
for instance in self.instances:
|
||||
if not instance in hidden:
|
||||
instance.render()
|
||||
|
||||
CGLUtils.render_tensor_post()
|
||||
if self.msaa:
|
||||
CGLUtils.blit_buffer(self.width, self.height, self.fbo_ms, self.fbo)
|
||||
|
||||
return self.readbuffer_to_tensor(modes)
|
Loading…
Reference in New Issue