Merge pull request #37 from fxia22/physics_render
renderer update, installation update
This commit is contained in:
commit
dd6398c771
|
@ -72,3 +72,4 @@ gibson/assets
|
|||
.cache
|
||||
notebook
|
||||
build
|
||||
dist
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -0,0 +1,5 @@
|
|||
include LICENSE
|
||||
|
||||
recursive-include gibson2/core *
|
||||
|
||||
include gibson2/global_config.yaml
|
|
@ -0,0 +1,10 @@
|
|||
from gibson2.core.simulator_flex import Simulator_Flex
|
||||
import numpy as np
|
||||
|
||||
config_path = '/scr/yxjin/nvidia/sw/devrel/libdev/flex/dev/rbd/demo/gym/cfg/gibson.yaml'
|
||||
bin_path = '/scr/yxjin/nvidia/sw/devrel/libdev/flex/dev/rbd/bin'
|
||||
|
||||
simulator = Simulator_Flex(config_path, bin_path)
|
||||
|
||||
while True:
|
||||
simulator.step(np.array([[0,0,0,0,0,0,0,0]]))
|
|
@ -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'):
|
||||
|
|
|
@ -0,0 +1,82 @@
|
|||
import yaml
|
||||
from gibson2.core.physics.robot_locomotors import Turtlebot
|
||||
from gibson2.core.simulator import Simulator
|
||||
from gibson2.core.physics.scene import BuildingScene, StadiumScene
|
||||
from gibson2.utils.utils import parse_config
|
||||
from gibson2.core.physics.interactive_objects import YCBObject, SoftObject
|
||||
import pytest
|
||||
import pybullet as p
|
||||
import numpy as np
|
||||
import time
|
||||
import random
|
||||
|
||||
config = parse_config('../configs/turtlebot_p2p_nav.yaml')
|
||||
|
||||
s = Simulator(mode='gui', resolution=512, render_to_tensor=False)
|
||||
scene = BuildingScene('Ohoopee')
|
||||
s.import_scene(scene)
|
||||
turtlebot = Turtlebot(config)
|
||||
s.import_robot(turtlebot)
|
||||
|
||||
# soft bunny
|
||||
# obj = SoftObject(filename = '/scr/yxjin/assets/models/bunny/bunny.obj', basePosition = [0.5, 0.1, 1.0], mass = 0.1, useNeoHookean = 1, NeoHookeanMu = 20, NeoHookeanLambda = 20, NeoHookeanDamping = 0.001, useSelfCollision = 1, frictionCoeff = .5, collisionMargin = 0.045)
|
||||
# s.import_object(obj)
|
||||
|
||||
# cloth
|
||||
obj = SoftObject(filename = '/scr/yxjin/assets/models/cloth/cloth_z_up_highres.obj', basePosition = [0.6, 0, 0.7], mass = 0.1, useNeoHookean = 0, useBendingSprings=1,useMassSpring=1, springElasticStiffness=40, springDampingStiffness=.1, useSelfCollision = 0, frictionCoeff = .5, useFaceContact = 1, collisionMargin = 0.045)
|
||||
s.import_object(obj)
|
||||
obj.addAnchor(nodeIndex=0)
|
||||
obj.addAnchor(nodeIndex=2)
|
||||
|
||||
##### BENCHMART CODE START #####
|
||||
# multiple objects
|
||||
# for i in range(4):
|
||||
# # random quaternion (not UNIFORM!)
|
||||
# w = random.uniform(0, 1)
|
||||
# qsum = w
|
||||
# x = random.uniform(0, 1) * (1 - qsum)
|
||||
# qsum += x
|
||||
# y = random.uniform(0, 1) * (1 - qsum)
|
||||
# qsum += y
|
||||
# z = random.uniform(0, 1) * (1 - qsum)
|
||||
# bunny = SoftObject(filename = '/scr/yxjin/assets/models/bunny/bunny.obj', basePosition = [0.2, 0.2, 1.8+i*0.3], baseOrientation= [x, y, z, w], mass = 0.1, useNeoHookean = 1, NeoHookeanMu = 20, NeoHookeanLambda = 20, NeoHookeanDamping = 0.001, useSelfCollision = 1, frictionCoeff = .5)
|
||||
# s.import_object(bunny)
|
||||
|
||||
# for i in range(1):
|
||||
# cloth = SoftObject(filename = '/scr/yxjin/assets/models/cloth/cloth_z_up_highres.obj', basePosition = [0.2, 0.2, 0.7+0.3*i], mass = 0.1, useNeoHookean = 0, useBendingSprings=1,useMassSpring=1, springElasticStiffness=40, springDampingStiffness=.1, useSelfCollision = 0, frictionCoeff = .5, useFaceContact = 1)
|
||||
# s.import_object(cloth)
|
||||
##### BENCHMART CODE END #####
|
||||
|
||||
# print('start timing ...')
|
||||
# start_time = time.time()
|
||||
for i in range(2000):
|
||||
turtlebot.apply_action([0.5,0.5])
|
||||
|
||||
##### BENCHMART CODE START #####
|
||||
# if i % 80 == 0 and i < 600:
|
||||
# # random quaternion (not UNIFORM!)
|
||||
# w = random.uniform(0, 1)
|
||||
# qsum = w
|
||||
# x = random.uniform(0, 1) * (1 - qsum)
|
||||
# qsum += x
|
||||
# y = random.uniform(0, 1) * (1 - qsum)
|
||||
# qsum += y
|
||||
# z = random.uniform(0, 1) * (1 - qsum)
|
||||
|
||||
# if i == 240 or i == 480:
|
||||
# bunny = SoftObject(filename = '/scr/yxjin/assets/models/bunny/bunny.obj', basePosition = [0.2, 0.2, 1.5], baseOrientation= [x, y, z, w], mass = 0.1, useNeoHookean = 1, NeoHookeanMu = 20, NeoHookeanLambda = 20, NeoHookeanDamping = 0.001, useSelfCollision = 1, frictionCoeff = .5)
|
||||
# s.import_object(bunny)
|
||||
# elif i == 0 or i == 320:
|
||||
# obj = YCBObject('003_cracker_box')
|
||||
# s.import_object(obj)
|
||||
# else:
|
||||
# cloth = SoftObject(filename = '/scr/yxjin/assets/models/cloth/cloth_z_up_highres.obj', basePosition = [0.2, 0.2, 1.5], baseOrientation= [x, y, z, w], mass = 0.1, useNeoHookean = 0, useBendingSprings=1,useMassSpring=1, springElasticStiffness=40, springDampingStiffness=.1, useSelfCollision = 0, frictionCoeff = .5, useFaceContact = 1)
|
||||
# s.import_object(cloth)
|
||||
##### BENCHMART CODE END #####
|
||||
|
||||
s.step()
|
||||
rgb = s.renderer.render_robot_cameras(modes=('rgb'))
|
||||
# used_time = time.time() - start_time
|
||||
# print("duration: %s seconds, fps: %s" % (used_time, 2000/used_time))
|
||||
|
||||
s.disconnect()
|
|
@ -22,7 +22,7 @@ class YCBObject(object):
|
|||
|
||||
body_id = p.createMultiBody(baseCollisionShapeIndex=collision_id,
|
||||
baseVisualShapeIndex=visual_id,
|
||||
basePosition=[0, 0, 0],
|
||||
basePosition=[0.2, 0.2, 1.5],
|
||||
baseMass=0.1)
|
||||
|
||||
self.body_id = body_id
|
||||
|
@ -216,6 +216,41 @@ class InteractiveObj(object):
|
|||
p.resetBasePositionAndOrientation(self.body_id, pos, orn)
|
||||
|
||||
|
||||
class SoftObject(object):
|
||||
def __init__(self, filename, basePosition=[0,0,0], baseOrientation=[0,0,0,1], scale=-1, mass=-1, collisionMargin=-1, useMassSpring=0, useBendingSprings=0, useNeoHookean=0, springElasticStiffness=1, springDampingStiffness=0.1, springBendingStiffness=0.1, NeoHookeanMu=1, NeoHookeanLambda=1, NeoHookeanDamping=0.1, frictionCoeff=0, useFaceContact=0, useSelfCollision=0):
|
||||
self.filename = filename
|
||||
self.scale = scale
|
||||
self.basePosition = basePosition
|
||||
self.baseOrientation = baseOrientation
|
||||
self.mass = mass
|
||||
self.collisionMargin = collisionMargin
|
||||
self.useMassSpring = useMassSpring
|
||||
self.useBendingSprings = useBendingSprings
|
||||
self.useNeoHookean = useNeoHookean
|
||||
self.springElasticStiffness = springElasticStiffness
|
||||
self.springDampingStiffness = springDampingStiffness
|
||||
self.springBendingStiffness = springBendingStiffness
|
||||
self.NeoHookeanMu = NeoHookeanMu
|
||||
self.NeoHookeanLambda = NeoHookeanLambda
|
||||
self.NeoHookeanDamping = NeoHookeanDamping
|
||||
self.frictionCoeff = frictionCoeff
|
||||
self.useFaceContact = useFaceContact
|
||||
self.useSelfCollision = useSelfCollision
|
||||
self.body_id = None
|
||||
|
||||
def load(self):
|
||||
self.body_id = p.loadSoftBody(self.filename, scale = self.scale, basePosition = self.basePosition, baseOrientation = self.baseOrientation, mass=self.mass, collisionMargin=self.collisionMargin, useMassSpring=self.useMassSpring, useBendingSprings=self.useBendingSprings, useNeoHookean=self.useNeoHookean, springElasticStiffness=self.springElasticStiffness, springDampingStiffness=self.springDampingStiffness, springBendingStiffness=self.springBendingStiffness, NeoHookeanMu=self.NeoHookeanMu, NeoHookeanLambda=self.NeoHookeanLambda, NeoHookeanDamping=self.NeoHookeanDamping, frictionCoeff=self.frictionCoeff, useFaceContact=self.useFaceContact, useSelfCollision=self.useSelfCollision)
|
||||
|
||||
# Set signed distance function voxel size (integrate to Simulator class?)
|
||||
p.setPhysicsEngineParameter(sparseSdfVoxelSize=0.1)
|
||||
|
||||
return self.body_id
|
||||
|
||||
def addAnchor(self, nodeIndex=-1, bodyUniqueId=-1, linkIndex=-1, bodyFramePosition=[0,0,0], physicsClientId=0):
|
||||
p.createSoftBodyAnchor(self.body_id, nodeIndex, bodyUniqueId, linkIndex, bodyFramePosition, physicsClientId)
|
||||
|
||||
|
||||
|
||||
class RBOObject(InteractiveObj):
|
||||
def __init__(self, name, scale=1):
|
||||
filename = os.path.join(gibson2.assets_path, 'models', 'rbo', name, 'configuration',
|
||||
|
|
|
@ -64,6 +64,22 @@ class StadiumScene(Scene):
|
|||
|
||||
def get_floor_height(self, floor):
|
||||
return 0.0
|
||||
|
||||
|
||||
|
||||
class InteractiveBuildingScene(Scene):
|
||||
"""
|
||||
A simple stadium scene for debugging
|
||||
"""
|
||||
|
||||
def __init__(self, path):
|
||||
self.path = path
|
||||
|
||||
def load(self):
|
||||
filename = self.path
|
||||
body_id = p.loadURDF(filename, flags=p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS)
|
||||
return [body_id]
|
||||
|
||||
|
||||
|
||||
class StadiumSceneInteractive(Scene):
|
||||
|
|
|
@ -12,23 +12,36 @@ 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(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(GLFWRendererContext PRIVATE pybind11::module dl glfw ${GLFW_LIBRARIES})
|
||||
else ()
|
||||
target_link_libraries(MeshRendererContext 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(tinyobjloader PROPERTIES PREFIX "${PYTHON_MODULE_PREFIX}"
|
||||
SUFFIX "${PYTHON_MODULE_EXTENSION}")
|
||||
|
||||
|
|
|
@ -23,6 +23,9 @@
|
|||
#include <cuda_runtime.h>
|
||||
#include <cuda_gl_interop.h>
|
||||
|
||||
#define STB_IMAGE_IMPLEMENTATION
|
||||
#include "stb_image.h"
|
||||
|
||||
#define MAX_NUM_RESOURCES 10
|
||||
|
||||
namespace py = pybind11;
|
||||
|
@ -365,17 +368,422 @@ public:
|
|||
std::cout << "cudaGraphicsUnmapResources failed: " << err << std::endl;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
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);
|
||||
}
|
||||
|
||||
void render_meshrenderer_post() {
|
||||
glDisable(GL_DEPTH_TEST);
|
||||
}
|
||||
|
||||
void glad_init() {
|
||||
if (!gladLoadGL(eglGetProcAddress)) {
|
||||
fprintf(stderr, "failed to load GL with glad.\n");
|
||||
exit(EXIT_FAILURE);
|
||||
}
|
||||
}
|
||||
|
||||
std::string getstring_meshrenderer() {
|
||||
return reinterpret_cast<char const *>(glGetString(GL_VERSION));
|
||||
}
|
||||
|
||||
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);
|
||||
}
|
||||
else if (!strcmp(mode, "normal")) {
|
||||
glReadBuffer(GL_COLOR_ATTACHMENT1);
|
||||
}
|
||||
else if (!strcmp(mode, "seg")) {
|
||||
glReadBuffer(GL_COLOR_ATTACHMENT2);
|
||||
}
|
||||
else if (!strcmp(mode, "3d")) {
|
||||
glReadBuffer(GL_COLOR_ATTACHMENT3);
|
||||
}
|
||||
else {
|
||||
fprintf(stderr, "unknown buffer mode.\n");
|
||||
exit(EXIT_FAILURE);
|
||||
}
|
||||
py::array_t<float> data = py::array_t<float>(4 * width * height);
|
||||
py::buffer_info buf = data.request();
|
||||
float* ptr = (float *) buf.ptr;
|
||||
glReadPixels(0, 0, width, height, GL_RGBA, GL_FLOAT, ptr);
|
||||
return data;
|
||||
}
|
||||
|
||||
void clean_meshrenderer(std::vector<GLuint> texture1, std::vector<GLuint> texture2, std::vector<GLuint> fbo, std::vector<GLuint> vaos, std::vector<GLuint> vbos) {
|
||||
glDeleteTextures(texture1.size(), texture1.data());
|
||||
glDeleteTextures(texture2.size(), texture2.data());
|
||||
glDeleteFramebuffers(fbo.size(), fbo.data());
|
||||
glDeleteBuffers(vaos.size(), vaos.data());
|
||||
glDeleteBuffers(vbos.size(), vbos.data());
|
||||
}
|
||||
|
||||
py::list setup_framebuffer_meshrenderer(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, color_tex_rgb);
|
||||
glTexImage2D(GL_TEXTURE_2D, 0, GL_RGBA, width, height, 0, GL_RGBA, GL_UNSIGNED_BYTE, NULL);
|
||||
glBindTexture(GL_TEXTURE_2D, color_tex_normal);
|
||||
glTexImage2D(GL_TEXTURE_2D, 0, GL_RGBA, width, height, 0, GL_RGBA, GL_UNSIGNED_BYTE, NULL);
|
||||
glBindTexture(GL_TEXTURE_2D, color_tex_semantics);
|
||||
glTexImage2D(GL_TEXTURE_2D, 0, GL_RGBA, width, height, 0, GL_RGBA, GL_UNSIGNED_BYTE, NULL);
|
||||
glBindTexture(GL_TEXTURE_2D, color_tex_3d);
|
||||
glTexImage2D(GL_TEXTURE_2D, 0, GL_RGBA, width, height, 0, GL_RGBA, GL_UNSIGNED_BYTE, NULL);
|
||||
glBindTexture(GL_TEXTURE_2D, depth_tex);
|
||||
glTexImage2D(GL_TEXTURE_2D, 0, GL_DEPTH24_STENCIL8, width, height, 0, GL_DEPTH_STENCIL, GL_UNSIGNED_INT_24_8, NULL);
|
||||
glBindFramebuffer(GL_FRAMEBUFFER, fbo);
|
||||
glFramebufferTexture2D(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT0, GL_TEXTURE_2D, color_tex_rgb, 0);
|
||||
glFramebufferTexture2D(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT1, GL_TEXTURE_2D, color_tex_normal, 0);
|
||||
glFramebufferTexture2D(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT2, GL_TEXTURE_2D, color_tex_semantics, 0);
|
||||
glFramebufferTexture2D(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT3, GL_TEXTURE_2D, color_tex_3d, 0);
|
||||
glFramebufferTexture2D(GL_FRAMEBUFFER, GL_DEPTH_STENCIL_ATTACHMENT, GL_TEXTURE_2D, 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 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);
|
||||
glCompileShader(vertexShader);
|
||||
int success;
|
||||
char infoLog[512];
|
||||
glGetShaderiv(vertexShader, GL_COMPILE_STATUS, &success);
|
||||
if (!success)
|
||||
{
|
||||
glGetShaderInfoLog(vertexShader, 512, NULL, infoLog);
|
||||
std::cout << "ERROR::SHADER::VERTEX::COMPILATION_FAILED\n" << infoLog << std::endl;
|
||||
}
|
||||
int fragmentShader = glCreateShader(GL_FRAGMENT_SHADER);
|
||||
glShaderSource(fragmentShader, 1, &fragmentShaderSource, NULL);
|
||||
glCompileShader(fragmentShader);
|
||||
glGetShaderiv(fragmentShader, GL_COMPILE_STATUS, &success);
|
||||
if (!success)
|
||||
{
|
||||
glGetShaderInfoLog(fragmentShader, 512, NULL, infoLog);
|
||||
std::cout << "ERROR::SHADER::FRAGMENT::COMPILATION_FAILED\n" << infoLog << std::endl;
|
||||
}
|
||||
int shaderProgram = glCreateProgram();
|
||||
glAttachShader(shaderProgram, vertexShader);
|
||||
glAttachShader(shaderProgram, fragmentShader);
|
||||
glLinkProgram(shaderProgram);
|
||||
glGetProgramiv(shaderProgram, GL_LINK_STATUS, &success);
|
||||
if (!success) {
|
||||
glGetProgramInfoLog(shaderProgram, 512, NULL, infoLog);
|
||||
std::cout << "ERROR::SHADER::PROGRAM::LINKING_FAILED\n" << infoLog << std::endl;
|
||||
}
|
||||
glDeleteShader(vertexShader);
|
||||
glDeleteShader(fragmentShader);
|
||||
int texUnitUniform = glGetUniformLocation(shaderProgram, "texUnit");
|
||||
py::list result;
|
||||
result.append(shaderProgram);
|
||||
result.append(texUnitUniform);
|
||||
return result;
|
||||
}
|
||||
|
||||
py::list load_object_meshrenderer(int shaderProgram, py::array_t<float> vertexData) {
|
||||
GLuint VAO;
|
||||
glGenVertexArrays(1, &VAO);
|
||||
glBindVertexArray(VAO);
|
||||
GLuint VBO;
|
||||
glGenBuffers(1, &VBO);
|
||||
glBindBuffer(GL_ARRAY_BUFFER, VBO);
|
||||
py::buffer_info buf = vertexData.request();
|
||||
float* ptr = (float *) buf.ptr;
|
||||
glBufferData(GL_ARRAY_BUFFER, vertexData.size()*sizeof(float), ptr, GL_STATIC_DRAW);
|
||||
GLuint positionAttrib = glGetAttribLocation(shaderProgram, "position");
|
||||
GLuint normalAttrib = glGetAttribLocation(shaderProgram, "normal");
|
||||
GLuint coordsAttrib = glGetAttribLocation(shaderProgram, "texCoords");
|
||||
glEnableVertexAttribArray(0);
|
||||
glEnableVertexAttribArray(1);
|
||||
glEnableVertexAttribArray(2);
|
||||
glVertexAttribPointer(positionAttrib, 3, GL_FLOAT, GL_FALSE, 32, (void*)0);
|
||||
glVertexAttribPointer(normalAttrib, 3, GL_FLOAT, GL_FALSE, 32, (void*)12);
|
||||
glVertexAttribPointer(coordsAttrib, 2, GL_FLOAT, GL_TRUE, 32, (void*)24);
|
||||
glBindBuffer(GL_ARRAY_BUFFER, 0);
|
||||
glBindVertexArray(0);
|
||||
py::list result;
|
||||
result.append(VAO);
|
||||
result.append(VBO);
|
||||
return result;
|
||||
}
|
||||
|
||||
void render_softbody_instance(int vao, int vbo, py::array_t<float> vertexData) {
|
||||
glBindVertexArray(vao);
|
||||
glBindBuffer(GL_ARRAY_BUFFER, vbo);
|
||||
py::buffer_info buf = vertexData.request();
|
||||
float* ptr = (float *) buf.ptr;
|
||||
glBufferData(GL_ARRAY_BUFFER, vertexData.size()*sizeof(float), ptr, GL_STATIC_DRAW);
|
||||
glBindBuffer(GL_ARRAY_BUFFER, 0);
|
||||
glBindVertexArray(0);
|
||||
}
|
||||
|
||||
void initvar_instance(int shaderProgram, py::array_t<float> V, py::array_t<float> P, py::array_t<float> pose_trans, py::array_t<float> pose_rot, py::array_t<float> lightpos, py::array_t<float> lightcolor) {
|
||||
glUseProgram(shaderProgram);
|
||||
float *Vptr = (float *) V.request().ptr;
|
||||
float *Pptr = (float *) P.request().ptr;
|
||||
float *transptr = (float *) pose_trans.request().ptr;
|
||||
float *rotptr = (float *) pose_rot.request().ptr;
|
||||
float *lightposptr = (float *) lightpos.request().ptr;
|
||||
float *lightcolorptr = (float *) lightcolor.request().ptr;
|
||||
glUniformMatrix4fv(glGetUniformLocation(shaderProgram, "V"), 1, GL_TRUE, Vptr);
|
||||
glUniformMatrix4fv(glGetUniformLocation(shaderProgram, "P"), 1, GL_FALSE, Pptr);
|
||||
glUniformMatrix4fv(glGetUniformLocation(shaderProgram, "pose_trans"), 1, GL_FALSE, transptr);
|
||||
glUniformMatrix4fv(glGetUniformLocation(shaderProgram, "pose_rot"), 1, GL_TRUE, rotptr);
|
||||
glUniform3f(glGetUniformLocation(shaderProgram, "light_position"), lightposptr[0], lightposptr[1], lightposptr[2]);
|
||||
glUniform3f(glGetUniformLocation(shaderProgram, "light_color"), lightcolorptr[0], lightcolorptr[1], lightcolorptr[2]);
|
||||
}
|
||||
|
||||
void init_material_instance(int shaderProgram, float instance_color, py::array_t<float> diffuse_color, float use_texture) {
|
||||
float *diffuse_ptr = (float *) diffuse_color.request().ptr;
|
||||
glUniform3f(glGetUniformLocation(shaderProgram, "instance_color"), instance_color, 0, 0);
|
||||
glUniform3f(glGetUniformLocation(shaderProgram, "diffuse_color"), diffuse_ptr[0], diffuse_ptr[1], diffuse_ptr[2]);
|
||||
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, 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);
|
||||
|
||||
}
|
||||
|
||||
void initvar_instance_group(int shaderProgram, py::array_t<float> V, py::array_t<float> P, py::array_t<float> lightpos, py::array_t<float> lightcolor) {
|
||||
glUseProgram(shaderProgram);
|
||||
float *Vptr = (float *) V.request().ptr;
|
||||
float *Pptr = (float *) P.request().ptr;
|
||||
float *lightposptr = (float *) lightpos.request().ptr;
|
||||
float *lightcolorptr = (float *) lightcolor.request().ptr;
|
||||
glUniformMatrix4fv(glGetUniformLocation(shaderProgram, "V"), 1, GL_TRUE, Vptr);
|
||||
glUniformMatrix4fv(glGetUniformLocation(shaderProgram, "P"), 1, GL_FALSE, Pptr);
|
||||
glUniform3f(glGetUniformLocation(shaderProgram, "light_position"), lightposptr[0], lightposptr[1], lightposptr[2]);
|
||||
glUniform3f(glGetUniformLocation(shaderProgram, "light_color"), lightcolorptr[0], lightcolorptr[1], lightcolorptr[2]);
|
||||
}
|
||||
|
||||
void init_material_pos_instance(int shaderProgram, py::array_t<float> pose_trans, py::array_t<float> pose_rot, float instance_color, py::array_t<float> diffuse_color, float use_texture) {
|
||||
float *transptr = (float *) pose_trans.request().ptr;
|
||||
float *rotptr = (float *) pose_rot.request().ptr;
|
||||
float *diffuse_ptr = (float *) diffuse_color.request().ptr;
|
||||
glUniformMatrix4fv(glGetUniformLocation(shaderProgram, "pose_trans"), 1, GL_FALSE, transptr);
|
||||
glUniformMatrix4fv(glGetUniformLocation(shaderProgram, "pose_rot"), 1, GL_TRUE, rotptr);
|
||||
glUniform3f(glGetUniformLocation(shaderProgram, "instance_color"), instance_color, 0, 0);
|
||||
glUniform3f(glGetUniformLocation(shaderProgram, "diffuse_color"), diffuse_ptr[0], diffuse_ptr[1], diffuse_ptr[2]);
|
||||
glUniform1f(glGetUniformLocation(shaderProgram, "use_texture"), use_texture);
|
||||
}
|
||||
|
||||
|
||||
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);
|
||||
}
|
||||
|
||||
void cglBindVertexArray(int vao) {
|
||||
glBindVertexArray(vao);
|
||||
}
|
||||
|
||||
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(MeshRendererContext, m) {
|
||||
py::class_<MeshRendererContext>(m, "MeshRendererContext")
|
||||
.def(py::init<int, int, int>())
|
||||
.def("init", &MeshRendererContext::init)
|
||||
.def("release", &MeshRendererContext::release)
|
||||
.def("map_tensor", &MeshRendererContext::map_tensor)
|
||||
.def("map_tensor_float", &MeshRendererContext::map_tensor_float);
|
||||
py::class_<MeshRendererContext> pymodule = py::class_<MeshRendererContext>(m, "MeshRendererContext");
|
||||
|
||||
pymodule.def(py::init<int, int, int>());
|
||||
pymodule.def("init", &MeshRendererContext::init);
|
||||
pymodule.def("release", &MeshRendererContext::release);
|
||||
pymodule.def("map_tensor", &MeshRendererContext::map_tensor);
|
||||
pymodule.def("map_tensor_float", &MeshRendererContext::map_tensor_float);
|
||||
|
||||
// class MeshRenderer
|
||||
pymodule.def("render_meshrenderer_pre", &MeshRendererContext::render_meshrenderer_pre, "pre-executed functions in MeshRenderer.render");
|
||||
pymodule.def("render_meshrenderer_post", &MeshRendererContext::render_meshrenderer_post, "post-executed functions in MeshRenderer.render");
|
||||
pymodule.def("getstring_meshrenderer", &MeshRendererContext::getstring_meshrenderer, "return GL version string");
|
||||
pymodule.def("readbuffer_meshrenderer", &MeshRendererContext::readbuffer_meshrenderer, "read pixel buffer");
|
||||
pymodule.def("glad_init", &MeshRendererContext::glad_init, "init glad");
|
||||
pymodule.def("clean_meshrenderer", &MeshRendererContext::clean_meshrenderer, "clean meshrenderer");
|
||||
pymodule.def("setup_framebuffer_meshrenderer", &MeshRendererContext::setup_framebuffer_meshrenderer, "setup framebuffer in meshrenderer");
|
||||
pymodule.def("setup_framebuffer_meshrenderer_ms", &MeshRendererContext::setup_framebuffer_meshrenderer_ms, "setup framebuffer in meshrenderer with MSAA");
|
||||
pymodule.def("blit_buffer", &MeshRendererContext::blit_buffer, "blit buffer");
|
||||
|
||||
pymodule.def("compile_shader_meshrenderer", &MeshRendererContext::compile_shader_meshrenderer, "compile vertex and fragment shader");
|
||||
pymodule.def("load_object_meshrenderer", &MeshRendererContext::load_object_meshrenderer, "load object into VAO and VBO");
|
||||
pymodule.def("loadTexture", &MeshRendererContext::loadTexture, "load texture function");
|
||||
|
||||
// class MeshRendererG2G
|
||||
pymodule.def("render_tensor_pre", &MeshRendererContext::render_tensor_pre, "pre-executed functions in MeshRendererG2G.render");
|
||||
pymodule.def("render_tensor_post", &MeshRendererContext::render_tensor_post, "post-executed functions in MeshRendererG2G.render");
|
||||
|
||||
// class Instance
|
||||
pymodule.def("render_softbody_instance", &MeshRendererContext::render_softbody_instance, "render softbody in instance.render");
|
||||
pymodule.def("initvar_instance", &MeshRendererContext::initvar_instance, "init uniforms in instance.render");
|
||||
pymodule.def("init_material_instance", &MeshRendererContext::init_material_instance, "init materials in instance.render");
|
||||
pymodule.def("draw_elements_instance", &MeshRendererContext::draw_elements_instance, "draw elements in instance.render and instancegroup.render");
|
||||
|
||||
// class InstanceGroup
|
||||
pymodule.def("initvar_instance_group", &MeshRendererContext::initvar_instance_group, "init uniforms in instancegroup.render");
|
||||
pymodule.def("init_material_pos_instance", &MeshRendererContext::init_material_pos_instance, "init materials and position in instancegroup.render");
|
||||
|
||||
// misc
|
||||
pymodule.def("cglBindVertexArray", &MeshRendererContext::cglBindVertexArray, "binding function");
|
||||
pymodule.def("cglUseProgram", &MeshRendererContext::cglUseProgram, "binding function");
|
||||
|
||||
|
||||
#ifdef VERSION_INFO
|
||||
m.attr("__version__") = VERSION_INFO;
|
||||
|
|
|
@ -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
|
|
@ -5,14 +5,13 @@ from PIL import Image
|
|||
Image.MAX_IMAGE_PIXELS = None
|
||||
|
||||
import gibson2.core.render.mesh_renderer.glutils.glcontext as glcontext
|
||||
import OpenGL.GL as GL
|
||||
import cv2
|
||||
import numpy as np
|
||||
#from pyassimp import load, release
|
||||
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
|
||||
from gibson2.core.render.mesh_renderer import MeshRendererContext, 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
|
||||
|
@ -97,58 +96,28 @@ class InstanceGroup(object):
|
|||
if self.renderer is None:
|
||||
return
|
||||
|
||||
GL.glUseProgram(self.renderer.shaderProgram)
|
||||
GL.glUniformMatrix4fv(GL.glGetUniformLocation(self.renderer.shaderProgram, 'V'), 1,
|
||||
GL.GL_TRUE, self.renderer.V)
|
||||
GL.glUniformMatrix4fv(GL.glGetUniformLocation(self.renderer.shaderProgram, 'P'), 1,
|
||||
GL.GL_FALSE, self.renderer.P)
|
||||
GL.glUniform3f(GL.glGetUniformLocation(self.renderer.shaderProgram, 'light_position'),
|
||||
*self.renderer.lightpos)
|
||||
GL.glUniform3f(GL.glGetUniformLocation(self.renderer.shaderProgram, 'light_color'),
|
||||
*self.renderer.lightcolor)
|
||||
self.renderer.r.initvar_instance_group(self.renderer.shaderProgram, self.renderer.V, self.renderer.P, self.renderer.lightpos, self.renderer.lightcolor)
|
||||
|
||||
for i, visual_object in enumerate(self.objects):
|
||||
for object_idx in visual_object.VAO_ids:
|
||||
|
||||
GL.glUniformMatrix4fv(
|
||||
GL.glGetUniformLocation(self.renderer.shaderProgram, 'pose_trans'), 1,
|
||||
GL.GL_FALSE, self.poses_trans[i])
|
||||
GL.glUniformMatrix4fv(
|
||||
GL.glGetUniformLocation(self.renderer.shaderProgram, 'pose_rot'), 1, GL.GL_TRUE,
|
||||
self.poses_rot[i])
|
||||
|
||||
GL.glUniform3f(
|
||||
GL.glGetUniformLocation(self.renderer.shaderProgram, 'instance_color'),
|
||||
float(self.class_id) / 255.0, 0, 0)
|
||||
|
||||
GL.glUniform3f(
|
||||
GL.glGetUniformLocation(self.renderer.shaderProgram, 'diffuse_color'),
|
||||
*self.renderer.materials_mapping[
|
||||
self.renderer.mesh_materials[object_idx]].kd[:3])
|
||||
GL.glUniform1f(
|
||||
GL.glGetUniformLocation(self.renderer.shaderProgram, 'use_texture'),
|
||||
float(self.renderer.materials_mapping[
|
||||
self.renderer.mesh_materials[object_idx]].is_texture()))
|
||||
|
||||
self.renderer.r.init_material_pos_instance(self.renderer.shaderProgram, self.poses_trans[i], self.poses_rot[i], float(self.class_id) / 255.0, self.renderer.materials_mapping[self.renderer.mesh_materials[object_idx]].kd[:3], float(self.renderer.materials_mapping[self.renderer.mesh_materials[object_idx]].is_texture()))
|
||||
|
||||
try:
|
||||
# Activate texture
|
||||
GL.glActiveTexture(GL.GL_TEXTURE0)
|
||||
texture_id = self.renderer.materials_mapping[self.renderer.mesh_materials[object_idx]].texture_id
|
||||
if texture_id is None:
|
||||
texture_id = -1
|
||||
|
||||
if self.renderer.materials_mapping[
|
||||
self.renderer.mesh_materials[object_idx]].is_texture():
|
||||
GL.glBindTexture(
|
||||
GL.GL_TEXTURE_2D, self.renderer.materials_mapping[
|
||||
self.renderer.mesh_materials[object_idx]].texture_id)
|
||||
if self.renderer.msaa:
|
||||
buffer = self.renderer.fbo_ms
|
||||
else:
|
||||
buffer = self.renderer.fbo
|
||||
|
||||
self.renderer.r.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)
|
||||
|
||||
GL.glUniform1i(self.renderer.texUnitUniform, 0)
|
||||
# Activate array
|
||||
GL.glBindVertexArray(self.renderer.VAOs[object_idx])
|
||||
# draw triangles
|
||||
GL.glDrawElements(GL.GL_TRIANGLES, self.renderer.faces[object_idx].size,
|
||||
GL.GL_UNSIGNED_INT, self.renderer.faces[object_idx])
|
||||
finally:
|
||||
GL.glBindVertexArray(0)
|
||||
GL.glUseProgram(0)
|
||||
self.renderer.r.cglBindVertexArray(0)
|
||||
self.renderer.r.cglUseProgram(0)
|
||||
|
||||
def get_pose_in_camera(self):
|
||||
mat = self.renderer.V.dot(self.pose_trans.T).dot(self.pose_rot).T
|
||||
|
@ -194,7 +163,7 @@ class Instance(object):
|
|||
"""
|
||||
InstanceGroup is one instance of a visual object. One visual object can have multiple instances to save memory.
|
||||
"""
|
||||
def __init__(self, object, id, class_id, pybullet_uuid, pose_trans, pose_rot, dynamic):
|
||||
def __init__(self, object, id, class_id, pybullet_uuid, pose_trans, pose_rot, dynamic, softbody):
|
||||
self.object = object
|
||||
self.pose_trans = pose_trans
|
||||
self.pose_rot = pose_rot
|
||||
|
@ -203,6 +172,7 @@ class Instance(object):
|
|||
self.renderer = object.renderer
|
||||
self.pybullet_uuid = pybullet_uuid
|
||||
self.dynamic = dynamic
|
||||
self.softbody = softbody
|
||||
|
||||
def render(self):
|
||||
"""
|
||||
|
@ -211,52 +181,54 @@ class Instance(object):
|
|||
if self.renderer is None:
|
||||
return
|
||||
|
||||
GL.glUseProgram(self.renderer.shaderProgram)
|
||||
GL.glUniformMatrix4fv(GL.glGetUniformLocation(self.renderer.shaderProgram, 'V'), 1,
|
||||
GL.GL_TRUE, self.renderer.V)
|
||||
GL.glUniformMatrix4fv(GL.glGetUniformLocation(self.renderer.shaderProgram, 'P'), 1,
|
||||
GL.GL_FALSE, self.renderer.P)
|
||||
GL.glUniformMatrix4fv(GL.glGetUniformLocation(self.renderer.shaderProgram, 'pose_trans'), 1,
|
||||
GL.GL_FALSE, self.pose_trans)
|
||||
GL.glUniformMatrix4fv(GL.glGetUniformLocation(self.renderer.shaderProgram, 'pose_rot'), 1,
|
||||
GL.GL_TRUE, self.pose_rot)
|
||||
GL.glUniform3f(GL.glGetUniformLocation(self.renderer.shaderProgram, 'light_position'),
|
||||
*self.renderer.lightpos)
|
||||
GL.glUniform3f(GL.glGetUniformLocation(self.renderer.shaderProgram, 'light_color'),
|
||||
*self.renderer.lightcolor)
|
||||
# softbody: reload vertex position
|
||||
if self.softbody:
|
||||
|
||||
# construct new vertex position into shape format
|
||||
object_idx = self.object.VAO_ids[0]
|
||||
vertices = p.getMeshData(self.pybullet_uuid)[1]
|
||||
vertices_flattened = [item for sublist in vertices for item in sublist]
|
||||
vertex_position = np.array(vertices_flattened).reshape((len(vertices_flattened)//3, 3))
|
||||
shape = self.renderer.shapes[object_idx]
|
||||
n_indices = len(shape.mesh.indices)
|
||||
np_indices = shape.mesh.numpy_indices().reshape((n_indices,3))
|
||||
shape_vertex_index = np_indices[:,0]
|
||||
shape_vertex = vertex_position[shape_vertex_index]
|
||||
|
||||
# update new vertex position in buffer data
|
||||
new_data = self.renderer.vertex_data[object_idx]
|
||||
new_data[:, 0:shape_vertex.shape[1]] = shape_vertex
|
||||
new_data = new_data.astype(np.float32)
|
||||
|
||||
# transform and rotation already included in mesh data
|
||||
self.pose_trans = np.eye(4)
|
||||
self.pose_rot = np.eye(4)
|
||||
|
||||
# update buffer data into VBO
|
||||
self.renderer.r.render_softbody_instance(self.renderer.VAOs[object_idx], self.renderer.VBOs[object_idx], new_data)
|
||||
|
||||
self.renderer.r.initvar_instance(self.renderer.shaderProgram, self.renderer.V, self.renderer.P, self.pose_trans, self.pose_rot, self.renderer.lightpos, self.renderer.lightcolor)
|
||||
|
||||
for object_idx in self.object.VAO_ids:
|
||||
GL.glUniform3f(GL.glGetUniformLocation(self.renderer.shaderProgram, 'instance_color'),
|
||||
float(self.class_id) / 255.0, 0, 0)
|
||||
GL.glUniform3f(
|
||||
GL.glGetUniformLocation(self.renderer.shaderProgram, 'diffuse_color'),
|
||||
*self.renderer.materials_mapping[self.renderer.mesh_materials[object_idx]].kd)
|
||||
GL.glUniform1f(
|
||||
GL.glGetUniformLocation(self.renderer.shaderProgram, 'use_texture'),
|
||||
float(self.renderer.materials_mapping[
|
||||
self.renderer.mesh_materials[object_idx]].is_texture()))
|
||||
|
||||
self.renderer.r.init_material_instance(self.renderer.shaderProgram, float(self.class_id) / 255.0, self.renderer.materials_mapping[self.renderer.mesh_materials[object_idx]].kd, float(self.renderer.materials_mapping[self.renderer.mesh_materials[object_idx]].is_texture()))
|
||||
|
||||
try:
|
||||
# Activate texture
|
||||
GL.glActiveTexture(GL.GL_TEXTURE0)
|
||||
texture_id = self.renderer.materials_mapping[self.renderer.mesh_materials[object_idx]].texture_id
|
||||
if texture_id is None:
|
||||
texture_id = -1
|
||||
|
||||
if self.renderer.materials_mapping[
|
||||
self.renderer.mesh_materials[object_idx]].is_texture():
|
||||
GL.glBindTexture(
|
||||
GL.GL_TEXTURE_2D, self.renderer.materials_mapping[
|
||||
self.renderer.mesh_materials[object_idx]].texture_id)
|
||||
if self.renderer.msaa:
|
||||
buffer = self.renderer.fbo_ms
|
||||
else:
|
||||
buffer = self.renderer.fbo
|
||||
|
||||
GL.glUniform1i(self.renderer.texUnitUniform, 0)
|
||||
# Activate array
|
||||
GL.glBindVertexArray(self.renderer.VAOs[object_idx])
|
||||
# draw triangles
|
||||
GL.glDrawElements(GL.GL_TRIANGLES, self.renderer.faces[object_idx].size,
|
||||
GL.GL_UNSIGNED_INT, self.renderer.faces[object_idx])
|
||||
self.renderer.r.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:
|
||||
GL.glBindVertexArray(0)
|
||||
self.renderer.r.cglBindVertexArray(0)
|
||||
|
||||
GL.glUseProgram(0)
|
||||
self.renderer.r.cglUseProgram(0)
|
||||
|
||||
def get_pose_in_camera(self):
|
||||
mat = self.renderer.V.dot(self.pose_trans.T).dot(self.pose_rot).T
|
||||
|
@ -298,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
|
||||
|
@ -315,6 +287,8 @@ class MeshRenderer:
|
|||
self.textures = []
|
||||
self.objects = []
|
||||
self.visual_objects = []
|
||||
self.vertex_data = []
|
||||
self.shapes = []
|
||||
|
||||
self.texUnitUniform = None
|
||||
self.width = width
|
||||
|
@ -334,44 +308,36 @@ 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()
|
||||
|
||||
self.glstring = GL.glGetString(GL.GL_VERSION)
|
||||
from OpenGL.GL import shaders
|
||||
self.shaders = shaders
|
||||
self.r.glad_init()
|
||||
self.glstring = self.r.getstring_meshrenderer()
|
||||
self.colors = colormap
|
||||
self.lightcolor = [1, 1, 1]
|
||||
|
||||
print("fisheye", self.fisheye)
|
||||
|
||||
if self.fisheye:
|
||||
vertexShader = self.shaders.compileShader(
|
||||
"".join(
|
||||
open(
|
||||
os.path.join(os.path.dirname(mesh_renderer.__file__),
|
||||
'shaders/fisheye_vert.shader')).readlines()).replace(
|
||||
"FISHEYE_SIZE", str(self.width / 2)), GL.GL_VERTEX_SHADER)
|
||||
fragmentShader = self.shaders.compileShader(
|
||||
"".join(
|
||||
open(
|
||||
os.path.join(os.path.dirname(mesh_renderer.__file__),
|
||||
'shaders/fisheye_frag.shader')).readlines()).replace(
|
||||
"FISHEYE_SIZE", str(self.width / 2)),
|
||||
GL.GL_FRAGMENT_SHADER)
|
||||
[self.shaderProgram, self.texUnitUniform] = self.r.compile_shader_meshrenderer(
|
||||
"".join(open(
|
||||
os.path.join(os.path.dirname(mesh_renderer.__file__),
|
||||
'shaders/fisheye_vert.shader')).readlines()).replace(
|
||||
"FISHEYE_SIZE", str(self.width / 2)),
|
||||
"".join(open(
|
||||
os.path.join(os.path.dirname(mesh_renderer.__file__),
|
||||
'shaders/fisheye_frag.shader')).readlines()).replace(
|
||||
"FISHEYE_SIZE", str(self.width / 2)))
|
||||
else:
|
||||
vertexShader = self.shaders.compileShader(
|
||||
"".join(
|
||||
open(
|
||||
os.path.join(os.path.dirname(mesh_renderer.__file__),
|
||||
'shaders/vert.shader')).readlines()), GL.GL_VERTEX_SHADER)
|
||||
fragmentShader = self.shaders.compileShader(
|
||||
"".join(
|
||||
open(
|
||||
os.path.join(os.path.dirname(mesh_renderer.__file__),
|
||||
'shaders/frag.shader')).readlines()), GL.GL_FRAGMENT_SHADER)
|
||||
self.shaderProgram = self.shaders.compileProgram(vertexShader, fragmentShader)
|
||||
self.texUnitUniform = GL.glGetUniformLocation(self.shaderProgram, 'texUnit')
|
||||
[self.shaderProgram, self.texUnitUniform] = self.r.compile_shader_meshrenderer(
|
||||
"".join(open(
|
||||
os.path.join(os.path.dirname(mesh_renderer.__file__),
|
||||
'shaders/vert.shader')).readlines()),
|
||||
"".join(open(
|
||||
os.path.join(os.path.dirname(mesh_renderer.__file__),
|
||||
'shaders/frag.shader')).readlines()))
|
||||
|
||||
self.lightpos = [0, 0, 0]
|
||||
self.setup_framebuffer()
|
||||
|
@ -391,53 +357,12 @@ class MeshRenderer:
|
|||
"""
|
||||
Set up RGB, surface normal, depth and segmentation framebuffers for the renderer
|
||||
"""
|
||||
self.fbo = GL.glGenFramebuffers(1)
|
||||
self.color_tex_rgb = GL.glGenTextures(1)
|
||||
self.color_tex_normal = GL.glGenTextures(1)
|
||||
self.color_tex_semantics = GL.glGenTextures(1)
|
||||
self.color_tex_3d = GL.glGenTextures(1)
|
||||
self.depth_tex = GL.glGenTextures(1)
|
||||
[self.fbo, self.color_tex_rgb, self.color_tex_normal, self.color_tex_semantics, self.color_tex_3d,
|
||||
self.depth_tex] = self.r.setup_framebuffer_meshrenderer(self.width, self.height)
|
||||
|
||||
GL.glBindTexture(GL.GL_TEXTURE_2D, self.color_tex_rgb)
|
||||
GL.glTexImage2D(GL.GL_TEXTURE_2D, 0, GL.GL_RGBA, self.width, self.height, 0, GL.GL_RGBA,
|
||||
GL.GL_UNSIGNED_BYTE, None)
|
||||
|
||||
GL.glBindTexture(GL.GL_TEXTURE_2D, self.color_tex_normal)
|
||||
GL.glTexImage2D(GL.GL_TEXTURE_2D, 0, GL.GL_RGBA, self.width, self.height, 0, GL.GL_RGBA,
|
||||
GL.GL_UNSIGNED_BYTE, None)
|
||||
|
||||
GL.glBindTexture(GL.GL_TEXTURE_2D, self.color_tex_semantics)
|
||||
GL.glTexImage2D(GL.GL_TEXTURE_2D, 0, GL.GL_RGBA, self.width, self.height, 0, GL.GL_RGBA,
|
||||
GL.GL_UNSIGNED_BYTE, None)
|
||||
|
||||
GL.glBindTexture(GL.GL_TEXTURE_2D, self.color_tex_3d)
|
||||
GL.glTexImage2D(GL.GL_TEXTURE_2D, 0, GL.GL_RGBA32F, self.width, self.height, 0, GL.GL_RGBA,
|
||||
GL.GL_FLOAT, None)
|
||||
|
||||
GL.glBindTexture(GL.GL_TEXTURE_2D, self.depth_tex)
|
||||
|
||||
GL.glTexImage2D.wrappedOperation(GL.GL_TEXTURE_2D, 0, GL.GL_DEPTH24_STENCIL8, self.width,
|
||||
self.height, 0, GL.GL_DEPTH_STENCIL,
|
||||
GL.GL_UNSIGNED_INT_24_8, None)
|
||||
|
||||
GL.glBindFramebuffer(GL.GL_FRAMEBUFFER, self.fbo)
|
||||
GL.glFramebufferTexture2D(GL.GL_FRAMEBUFFER, GL.GL_COLOR_ATTACHMENT0, GL.GL_TEXTURE_2D,
|
||||
self.color_tex_rgb, 0)
|
||||
GL.glFramebufferTexture2D(GL.GL_FRAMEBUFFER, GL.GL_COLOR_ATTACHMENT1, GL.GL_TEXTURE_2D,
|
||||
self.color_tex_normal, 0)
|
||||
GL.glFramebufferTexture2D(GL.GL_FRAMEBUFFER, GL.GL_COLOR_ATTACHMENT2, GL.GL_TEXTURE_2D,
|
||||
self.color_tex_semantics, 0)
|
||||
GL.glFramebufferTexture2D(GL.GL_FRAMEBUFFER, GL.GL_COLOR_ATTACHMENT3, GL.GL_TEXTURE_2D,
|
||||
self.color_tex_3d, 0)
|
||||
GL.glFramebufferTexture2D(GL.GL_FRAMEBUFFER, GL.GL_DEPTH_STENCIL_ATTACHMENT,
|
||||
GL.GL_TEXTURE_2D, self.depth_tex, 0)
|
||||
GL.glViewport(0, 0, self.width, self.height)
|
||||
GL.glDrawBuffers(4, [
|
||||
GL.GL_COLOR_ATTACHMENT0, GL.GL_COLOR_ATTACHMENT1, GL.GL_COLOR_ATTACHMENT2,
|
||||
GL.GL_COLOR_ATTACHMENT3
|
||||
])
|
||||
|
||||
assert GL.glCheckFramebufferStatus(GL.GL_FRAMEBUFFER) == GL.GL_FRAMEBUFFER_COMPLETE
|
||||
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] = self.r.setup_framebuffer_meshrenderer_ms(self.width, self.height)
|
||||
|
||||
def load_object(self,
|
||||
obj_path,
|
||||
|
@ -474,8 +399,8 @@ class MeshRenderer:
|
|||
|
||||
attrib = reader.GetAttrib()
|
||||
print("attrib.vertices = ", len(attrib.vertices))
|
||||
print("attrib.normals = ", len(attrib.normals))
|
||||
print("attrib.texcoords = ", len(attrib.texcoords))
|
||||
#print("attrib.normals = ", len(attrib.normals))
|
||||
#print("attrib.texcoords = ", len(attrib.texcoords))
|
||||
|
||||
materials = reader.GetMaterials()
|
||||
print("Num materials: ", len(materials))
|
||||
|
@ -498,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 = self.r.loadTexture(os.path.join(dir, item.diffuse_texname))
|
||||
material = Material('texture', texture_id=texture)
|
||||
self.textures.append(texture)
|
||||
else:
|
||||
|
@ -514,20 +440,20 @@ class MeshRenderer:
|
|||
elif len(materials) == 0: # urdf material not specified, but it is required
|
||||
self.materials_mapping[len(materials) + material_count] = Material('color', kd=[0.5, 0.5, 0.5])
|
||||
|
||||
print(self.materials_mapping)
|
||||
#print(self.materials_mapping)
|
||||
VAO_ids = []
|
||||
|
||||
vertex_position = np.array(attrib.vertices).reshape((len(attrib.vertices)//3, 3))
|
||||
vertex_normal = np.array(attrib.normals).reshape((len(attrib.normals)//3, 3))
|
||||
vertex_texcoord = np.array(attrib.texcoords).reshape((len(attrib.texcoords)//2, 2))
|
||||
print(vertex_position.shape, vertex_normal.shape, vertex_texcoord.shape)
|
||||
#print(vertex_position.shape, vertex_normal.shape, vertex_texcoord.shape)
|
||||
|
||||
|
||||
for shape in shapes:
|
||||
print(shape.name)
|
||||
#print(shape.name)
|
||||
material_id = shape.mesh.material_ids[0] # assume one shape only have one material
|
||||
print("material_id = {}".format(material_id))
|
||||
print("num_indices = {}".format(len(shape.mesh.indices)))
|
||||
#print("material_id = {}".format(material_id))
|
||||
#print("num_indices = {}".format(len(shape.mesh.indices)))
|
||||
n_indices = len(shape.mesh.indices)
|
||||
np_indices = shape.mesh.numpy_indices().reshape((n_indices,3))
|
||||
|
||||
|
@ -560,43 +486,20 @@ class MeshRenderer:
|
|||
|
||||
vertexData = vertices.astype(np.float32)
|
||||
|
||||
VAO = GL.glGenVertexArrays(1)
|
||||
GL.glBindVertexArray(VAO)
|
||||
|
||||
# Need VBO for triangle vertices and texture UV coordinates
|
||||
VBO = GL.glGenBuffers(1)
|
||||
GL.glBindBuffer(GL.GL_ARRAY_BUFFER, VBO)
|
||||
GL.glBufferData(GL.GL_ARRAY_BUFFER, vertexData.nbytes, vertexData, GL.GL_STATIC_DRAW)
|
||||
|
||||
# enable array and set up data
|
||||
positionAttrib = GL.glGetAttribLocation(self.shaderProgram, 'position')
|
||||
normalAttrib = GL.glGetAttribLocation(self.shaderProgram, 'normal')
|
||||
coordsAttrib = GL.glGetAttribLocation(self.shaderProgram, 'texCoords')
|
||||
|
||||
GL.glEnableVertexAttribArray(0)
|
||||
GL.glEnableVertexAttribArray(1)
|
||||
GL.glEnableVertexAttribArray(2)
|
||||
|
||||
GL.glVertexAttribPointer(positionAttrib, 3, GL.GL_FLOAT, GL.GL_FALSE, 32, None)
|
||||
GL.glVertexAttribPointer(normalAttrib, 3, GL.GL_FLOAT, GL.GL_FALSE, 32,
|
||||
ctypes.c_void_p(12))
|
||||
# the last parameter is a pointer
|
||||
GL.glVertexAttribPointer(coordsAttrib, 2, GL.GL_FLOAT, GL.GL_TRUE, 32,
|
||||
ctypes.c_void_p(24))
|
||||
|
||||
GL.glBindBuffer(GL.GL_ARRAY_BUFFER, 0)
|
||||
GL.glBindVertexArray(0)
|
||||
[VAO, VBO] = self.r.load_object_meshrenderer(self.shaderProgram, vertexData)
|
||||
|
||||
self.VAOs.append(VAO)
|
||||
self.VBOs.append(VBO)
|
||||
self.faces.append(faces)
|
||||
self.objects.append(obj_path)
|
||||
self.vertex_data.append(vertexData)
|
||||
self.shapes.append(shape)
|
||||
if material_id == -1: # if no material, use urdf color as material
|
||||
self.mesh_materials.append(len(materials) + material_count)
|
||||
else:
|
||||
self.mesh_materials.append(material_id + material_count)
|
||||
|
||||
print('mesh_materials', self.mesh_materials)
|
||||
#print('mesh_materials', self.mesh_materials)
|
||||
VAO_ids.append(self.get_num_objects() - 1)
|
||||
|
||||
#release(scene)
|
||||
|
@ -611,7 +514,8 @@ class MeshRenderer:
|
|||
class_id=0,
|
||||
pose_rot=np.eye(4),
|
||||
pose_trans=np.eye(4),
|
||||
dynamic=False):
|
||||
dynamic=False,
|
||||
softbody=False):
|
||||
"""
|
||||
Create instance for a visual object and link it to pybullet
|
||||
"""
|
||||
|
@ -621,7 +525,8 @@ class MeshRenderer:
|
|||
class_id=class_id,
|
||||
pose_trans=pose_trans,
|
||||
pose_rot=pose_rot,
|
||||
dynamic=dynamic)
|
||||
dynamic=dynamic,
|
||||
softbody=softbody)
|
||||
self.instances.append(instance)
|
||||
|
||||
def add_instance_group(self,
|
||||
|
@ -714,26 +619,22 @@ class MeshRenderer:
|
|||
"""
|
||||
results = []
|
||||
if 'rgb' in modes:
|
||||
GL.glReadBuffer(GL.GL_COLOR_ATTACHMENT0)
|
||||
frame = GL.glReadPixels(0, 0, self.width, self.height, GL.GL_RGBA, GL.GL_FLOAT)
|
||||
frame = self.r.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:
|
||||
GL.glReadBuffer(GL.GL_COLOR_ATTACHMENT1)
|
||||
normal = GL.glReadPixels(0, 0, self.width, self.height, GL.GL_RGBA, GL.GL_FLOAT)
|
||||
normal = self.r.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:
|
||||
GL.glReadBuffer(GL.GL_COLOR_ATTACHMENT2)
|
||||
seg = GL.glReadPixels(0, 0, self.width, self.height, GL.GL_RGBA, GL.GL_FLOAT)
|
||||
seg = self.r.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:
|
||||
GL.glReadBuffer(GL.GL_COLOR_ATTACHMENT3)
|
||||
pc = GL.glReadPixels(0, 0, self.width, self.height, GL.GL_RGBA, GL.GL_FLOAT)
|
||||
pc = self.r.readbuffer_meshrenderer('3d', self.width, self.height, self.fbo)
|
||||
pc = pc.reshape(self.height, self.width, 4)[::-1, :]
|
||||
results.append(pc)
|
||||
|
||||
|
@ -748,14 +649,18 @@ class MeshRenderer:
|
|||
hidden
|
||||
|
||||
"""
|
||||
GL.glClearColor(0, 0, 0, 1)
|
||||
GL.glClear(GL.GL_COLOR_BUFFER_BIT | GL.GL_DEPTH_BUFFER_BIT)
|
||||
GL.glEnable(GL.GL_DEPTH_TEST)
|
||||
if self.msaa:
|
||||
self.r.render_meshrenderer_pre(1, self.fbo_ms, self.fbo)
|
||||
else:
|
||||
self.r.render_meshrenderer_pre(0, 0, self.fbo)
|
||||
|
||||
for instance in self.instances:
|
||||
if not instance in hidden:
|
||||
instance.render()
|
||||
GL.glDisable(GL.GL_DEPTH_TEST)
|
||||
|
||||
self.r.render_meshrenderer_post()
|
||||
if self.msaa:
|
||||
self.r.blit_buffer(self.width, self.height, self.fbo_ms, self.fbo)
|
||||
|
||||
return self.readbuffer(modes)
|
||||
|
||||
|
@ -781,27 +686,34 @@ class MeshRenderer:
|
|||
"""
|
||||
Clean all the framebuffers, objects and instances
|
||||
"""
|
||||
GL.glDeleteTextures([
|
||||
clean_list = [
|
||||
self.color_tex_rgb, self.color_tex_normal, self.color_tex_semantics, self.color_tex_3d,
|
||||
self.depth_tex
|
||||
])
|
||||
]
|
||||
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]
|
||||
|
||||
self.r.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
|
||||
self.color_tex_3d = None
|
||||
self.depth_tex = None
|
||||
GL.glDeleteFramebuffers(1, [self.fbo])
|
||||
self.fbo = None
|
||||
GL.glDeleteBuffers(len(self.VAOs), self.VAOs)
|
||||
self.VAOs = []
|
||||
GL.glDeleteBuffers(len(self.VBOs), self.VBOs)
|
||||
self.VBOs = []
|
||||
GL.glDeleteTextures(self.textures)
|
||||
self.textures = []
|
||||
self.objects = [] # GC should free things here
|
||||
self.faces = [] # GC should free things here
|
||||
self.visual_objects = []
|
||||
self.instances = []
|
||||
self.vertex_data = []
|
||||
self.shapes = []
|
||||
|
||||
def transform_vector(self, vec):
|
||||
vec = np.array(vec)
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
import cv2
|
||||
import sys
|
||||
import numpy as np
|
||||
from gibson2.core.render.mesh_renderer.mesh_renderer_cpu import MeshRenderer, GL
|
||||
from gibson2.core.render.mesh_renderer.mesh_renderer_cpu import MeshRenderer
|
||||
import torch
|
||||
from gibson2.core.render.mesh_renderer.get_available_devices import get_cuda_device
|
||||
|
||||
|
@ -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):
|
||||
|
@ -20,6 +20,7 @@ class MeshRendererG2G(MeshRenderer):
|
|||
self.normal_tensor = torch.cuda.ByteTensor(height, width, 4).cuda()
|
||||
self.seg_tensor = torch.cuda.ByteTensor(height, width, 4).cuda()
|
||||
self.pc_tensor = torch.cuda.FloatTensor(height, width, 4).cuda()
|
||||
self.r.glad_init()
|
||||
|
||||
def readbuffer_to_tensor(self, modes=('rgb', 'normal', 'seg', '3d')):
|
||||
results = []
|
||||
|
@ -51,13 +52,17 @@ class MeshRendererG2G(MeshRenderer):
|
|||
hidden
|
||||
|
||||
"""
|
||||
GL.glClearColor(0, 0, 0, 1)
|
||||
GL.glClear(GL.GL_COLOR_BUFFER_BIT | GL.GL_DEPTH_BUFFER_BIT)
|
||||
GL.glEnable(GL.GL_DEPTH_TEST)
|
||||
if self.msaa:
|
||||
self.r.render_tensor_pre(1, self.fbo_ms, self.fbo)
|
||||
else:
|
||||
self.r.render_tensor_pre(0, 0, self.fbo)
|
||||
|
||||
for instance in self.instances:
|
||||
if not instance in hidden:
|
||||
instance.render()
|
||||
GL.glDisable(GL.GL_DEPTH_TEST)
|
||||
|
||||
self.r.render_tensor_post()
|
||||
if self.msaa:
|
||||
self.r.blit_buffer(self.width, self.height, self.fbo_ms, self.fbo)
|
||||
|
||||
return self.readbuffer_to_tensor(modes)
|
|
@ -41,7 +41,7 @@ class Viewer:
|
|||
self.renderer.set_camera(camera_pose, camera_pose + self.view_direction, [0, 0, 1])
|
||||
|
||||
if not self.renderer is None:
|
||||
frame = cv2.cvtColor(np.concatenate(self.renderer.render(modes=('rgb', 'seg')), axis=1),
|
||||
frame = cv2.cvtColor(np.concatenate(self.renderer.render(modes=('rgb')), axis=1),
|
||||
cv2.COLOR_RGB2BGR)
|
||||
else:
|
||||
frame = np.zeros((300, 300, 3)).astype(np.uint8)
|
||||
|
@ -66,7 +66,7 @@ class Viewer:
|
|||
exit()
|
||||
|
||||
if not self.renderer is None:
|
||||
frames = self.renderer.render_robot_cameras(modes=('rgb', 'seg'))
|
||||
frames = self.renderer.render_robot_cameras(modes=('rgb'))
|
||||
if len(frames) > 0:
|
||||
frame = cv2.cvtColor(np.concatenate(frames, axis=1), cv2.COLOR_RGB2BGR)
|
||||
cv2.imshow('robots', frame)
|
||||
|
|
|
@ -168,6 +168,9 @@ class Simulator:
|
|||
:param class_id: class_id to show for semantic segmentation mask
|
||||
"""
|
||||
new_object = object.load()
|
||||
isSoft = False
|
||||
if object.__class__.__name__ == 'SoftObject':
|
||||
isSoft = True
|
||||
self.objects.append(new_object)
|
||||
for shape in p.getVisualShapeData(new_object):
|
||||
id, link_id, type, dimensions, filename, rel_pos, rel_orn, color = shape[:8]
|
||||
|
@ -180,12 +183,14 @@ class Simulator:
|
|||
self.renderer.add_instance(len(self.renderer.visual_objects) - 1,
|
||||
pybullet_uuid=new_object,
|
||||
class_id=class_id,
|
||||
dynamic=True)
|
||||
dynamic=True,
|
||||
softbody=isSoft)
|
||||
else:
|
||||
self.renderer.add_instance(self.visual_objects[filename],
|
||||
pybullet_uuid=new_object,
|
||||
class_id=class_id,
|
||||
dynamic=True)
|
||||
dynamic=True,
|
||||
softbody=isSoft)
|
||||
elif type == p.GEOM_SPHERE:
|
||||
filename = os.path.join(gibson2.assets_path, 'models/mjcf_primitives/sphere8.obj')
|
||||
self.renderer.load_object(
|
||||
|
|
|
@ -0,0 +1,56 @@
|
|||
import os, sys, logging
|
||||
from time import time
|
||||
import numpy as np
|
||||
import pdb
|
||||
from flex_gym.flex_vec_env import set_flex_bin_path, FlexVecEnv
|
||||
from autolab_core import YamlConfig
|
||||
|
||||
class Simulator_Flex:
|
||||
def __init__(self, config_path, bin_path):
|
||||
logging.getLogger().setLevel(logging.INFO)
|
||||
self.config = YamlConfig(config_path)
|
||||
set_flex_bin_path(bin_path)
|
||||
self.env = FlexVecEnv(self.config)
|
||||
self.obs = self.env.reset()
|
||||
|
||||
def reset(self, agents_to_reset=None, get_info=False):
|
||||
self.env.reset(agents_to_reset=None, get_info=False)
|
||||
|
||||
def add_object(self, name, pos, scale):
|
||||
self.env.add_object(name, pos, scale)
|
||||
|
||||
def add_object_simple(self, name, pos, scale):
|
||||
self.env.add_object_simple(name, pos, scale)
|
||||
|
||||
def add_object_force(self, idx, pos):
|
||||
self.env.add_object_force(idx, pos)
|
||||
|
||||
def set_object_force(self, idx, pos):
|
||||
self.env.set_object_force(idx, pos)
|
||||
|
||||
def set_object_point_force(self, idx, pos, force):
|
||||
self.env.set_object_point_force(idx, pos, force)
|
||||
|
||||
def attach_visual_shape(self, name, idx, pos,rot, scale):
|
||||
self.env.attach_visual_shape(name, idx, pos,rot, scale)
|
||||
|
||||
def attach_visual_obj(self, name, idx, pos,rot, scale):
|
||||
self.env.attach_visual_obj(name, idx, pos,rot, scale)
|
||||
|
||||
def get_object_pose(self, idx):
|
||||
self.env.get_object_pose(idx)
|
||||
|
||||
def get_object_contacts(self):
|
||||
self.env.get_object_contacts()
|
||||
|
||||
def set_object_pose(self, idx, pose):
|
||||
self.env.set_object_pose(idx, pose)
|
||||
|
||||
def get_object_poses_in_camera(self, n):
|
||||
self.env.get_object_poses_in_camera(n)
|
||||
|
||||
def erase_visual_shape(self):
|
||||
self.env.rase_visual_shape()
|
||||
|
||||
def step(self, action):
|
||||
self.obs, _, _, _ = self.env.step(action)
|
|
@ -0,0 +1,47 @@
|
|||
import yaml
|
||||
from gibson2.core.physics.robot_locomotors import Turtlebot
|
||||
from gibson2.core.simulator import Simulator
|
||||
from gibson2.core.physics.scene import BuildingScene, StadiumScene
|
||||
from gibson2.utils.utils import parse_config
|
||||
import pytest
|
||||
import pybullet as p
|
||||
import numpy as np
|
||||
import os
|
||||
import gibson2
|
||||
|
||||
class Demo(object):
|
||||
def __init__(self):
|
||||
self.download_assets()
|
||||
|
||||
def download_assets(self):
|
||||
if not os.path.exists(gibson2.assets_path):
|
||||
os.system('wget https://storage.googleapis.com/gibsonassets/assets_gibson_v2.tar.gz -O /tmp/assets_gibson_v2.tar.gz')
|
||||
os.system('tar -zxf /tmp/assets_gibson_v2.tar.gz --directory {}'.format(os.path.dirname(gibson2.assets_path)))
|
||||
|
||||
if not os.path.exists(gibson2.dataset_path):
|
||||
os.makedirs(gibson2.dataset_path)
|
||||
if not os.path.exists(os.path.join(gibson2.dataset_path, 'Rs')):
|
||||
os.system('wget https://storage.googleapis.com/gibson_scenes/Rs.tar.gz -O /tmp/Rs.tar.gz')
|
||||
os.system('tar -zxf /tmp/Rs.tar.gz --directory {}'.format(gibson2.dataset_path))
|
||||
if not os.path.exists(os.path.join(gibson2.assets_path, 'turtlebot_p2p_nav_house.yaml')):
|
||||
os.system('wget https://storage.googleapis.com/gibson_scenes/turtlebot_p2p_nav_house.yaml \
|
||||
-O {}/turtlebot_p2p_nav_house.yaml'.format(gibson2.assets_path))
|
||||
|
||||
|
||||
def run_demo(self):
|
||||
config = parse_config(os.path.join(gibson2.assets_path,'turtlebot_p2p_nav_house.yaml'))
|
||||
|
||||
s = Simulator(mode='gui', resolution=700)
|
||||
scene = BuildingScene('Rs')
|
||||
s.import_scene(scene)
|
||||
turtlebot = Turtlebot(config)
|
||||
s.import_robot(turtlebot)
|
||||
|
||||
for i in range(1000):
|
||||
turtlebot.apply_action([0.1,0.5])
|
||||
s.step()
|
||||
|
||||
s.disconnect()
|
||||
|
||||
if __name__ == "__main__":
|
||||
Demo().run_demo()
|
|
@ -0,0 +1,48 @@
|
|||
import yaml
|
||||
from gibson2.core.physics.robot_locomotors import Turtlebot
|
||||
from gibson2.core.simulator import Simulator
|
||||
from gibson2.core.physics.scene import BuildingScene, StadiumScene, InteractiveBuildingScene
|
||||
from gibson2.utils.utils import parse_config
|
||||
import pytest
|
||||
import pybullet as p
|
||||
import numpy as np
|
||||
import os
|
||||
import gibson2
|
||||
|
||||
class DemoInteractive(object):
|
||||
def __init__(self):
|
||||
self.download_assets()
|
||||
|
||||
def download_assets(self):
|
||||
if not os.path.exists(gibson2.assets_path):
|
||||
os.system('wget https://storage.googleapis.com/gibsonassets/assets_gibson_v2.tar.gz -O /tmp/assets_gibson_v2.tar.gz')
|
||||
os.system('tar -zxf /tmp/assets_gibson_v2.tar.gz --directory {}'.format(os.path.dirname(gibson2.assets_path)))
|
||||
|
||||
if not os.path.exists(gibson2.dataset_path):
|
||||
os.makedirs(gibson2.dataset_path)
|
||||
if not os.path.exists(os.path.join(gibson2.dataset_path, 'Rs_interactive')):
|
||||
os.system('wget https://storage.googleapis.com/gibson_scenes/Rs_interactive.tar.gz -O /tmp/Rs_interactive.tar.gz')
|
||||
os.system('tar -zxf /tmp/Rs_interactive.tar.gz --directory {}'.format(gibson2.dataset_path))
|
||||
if not os.path.exists(os.path.join(gibson2.assets_path, 'turtlebot_p2p_nav_house.yaml')):
|
||||
os.system('wget https://storage.googleapis.com/gibson_scenes/turtlebot_p2p_nav_house.yaml \
|
||||
-O {}/turtlebot_p2p_nav_house.yaml'.format(gibson2.assets_path))
|
||||
|
||||
def run_demo(self):
|
||||
config = parse_config(os.path.join(gibson2.assets_path,'turtlebot_p2p_nav_house.yaml'))
|
||||
s = Simulator(mode='gui', resolution=700)
|
||||
model_path = os.path.join(gibson2.dataset_path, 'Rs_interactive', 'rs_interactive.urdf')
|
||||
scene = InteractiveBuildingScene(model_path)
|
||||
s.import_scene(scene)
|
||||
turtlebot = Turtlebot(config)
|
||||
s.import_robot(turtlebot)
|
||||
|
||||
for i in range(1000):
|
||||
turtlebot.apply_action([0.1,0.5])
|
||||
s.step()
|
||||
|
||||
s.disconnect()
|
||||
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
DemoInteractive().run_demo()
|
|
@ -829,7 +829,7 @@ class NavigateRandomEnv(NavigateEnv):
|
|||
|
||||
def reset(self):
|
||||
self.floor_num = self.scene.get_random_floor()
|
||||
self.scene.reset_floor(floor=self.floor_num, additional_elevation=0.05)
|
||||
self.scene.reset_floor(floor=self.floor_num, additional_elevation=0.02)
|
||||
state = super(NavigateRandomEnv, self).reset()
|
||||
return state
|
||||
|
||||
|
|
22
setup.py
22
setup.py
|
@ -101,32 +101,32 @@ class PostInstallCommand(install):
|
|||
|
||||
setup(
|
||||
name='gibson2',
|
||||
version=find_version('gibson2', '__init__.py'),
|
||||
version='0.0.2',
|
||||
author='Stanford University',
|
||||
zip_safe=False,
|
||||
packages=find_packages(),
|
||||
install_requires=[
|
||||
'numpy>=1.10.4',
|
||||
'pyglet>=1.2.0',
|
||||
'gym==0.12',
|
||||
'Pillow>=3.3.0',
|
||||
'PyYAML>=3.12',
|
||||
'numpy>=1.13',
|
||||
'pybullet==2.4.1',
|
||||
'transforms3d>=0.3.1',
|
||||
'tqdm == 4.19.9',
|
||||
'Pillow>=4.2.1',
|
||||
'Pillow==6.1',
|
||||
'matplotlib>=2.1.0',
|
||||
'cloudpickle>=0.4.1',
|
||||
'pygame>=1.9.3',
|
||||
'opencv-python',
|
||||
'torchvision==0.2.2',
|
||||
'aenum',
|
||||
'pyopengl==3.1.0',
|
||||
'pyopengl-accelerate==3.1.0',
|
||||
'pyassimp==4.1.3',
|
||||
'gputil'
|
||||
'gputil',
|
||||
'ipython',
|
||||
'networkx==2.0'
|
||||
],
|
||||
ext_modules=[CMakeExtension('MeshRendererContext', sourcedir='gibson2/core/render')],
|
||||
cmdclass=dict(build_ext=CMakeBuild),
|
||||
tests_require=[],
|
||||
package_data={'': [
|
||||
'gibson2/global_config.yaml',
|
||||
'gibson2/core/render/mesh_renderer/shaders/*'
|
||||
]},
|
||||
include_package_data=True,
|
||||
) #yapf: disable
|
||||
|
|
Loading…
Reference in New Issue