Merge branch 'release-cleanup' of https://github.com/fxia22/gibsonv2 into release-cleanup

This commit is contained in:
Chengshu Li 2020-04-02 00:52:06 -07:00
commit ea580a1374
14 changed files with 103 additions and 181 deletions

View File

@ -4,7 +4,6 @@ import numpy as np
from gibson2.core.render.mesh_renderer.mesh_renderer_tensor import MeshRendererG2G
from gibson2.core.render.profiler import Profiler
import matplotlib.pyplot as plt
import torch
if __name__ == '__main__':
model_path = sys.argv[1]

View File

@ -1,98 +0,0 @@
from gibson2.core.simulator import Simulator
from gibson2.core.physics.scene import BuildingScene, StadiumScene
from gibson2.core.physics.interactive_objects import Pedestrian
import networkx as nx
import matplotlib.pyplot as plt
import cv2
import gibson2
from PIL import Image
import numpy as np
import os
import pybullet as p
s = Simulator(mode='gui', resolution=512)
scene = BuildingScene("Maugansville")
ids = s.import_scene(scene)
print(ids)
trav_map = np.array(
Image.open(os.path.join(gibson2.dataset_path, 'Maugansville/floor_trav_1_v3.png')))
obstacle_map = np.array(Image.open(os.path.join(gibson2.dataset_path, 'Maugansville/floor_1.png')))
trav_map[obstacle_map == 0] = 0
trav_map = cv2.erode(trav_map, np.ones((30, 30)))
plt.figure(figsize=(12, 12))
plt.imshow(trav_map)
plt.show()
def dist(a, b):
(x1, y1) = a
(x2, y2) = b
return ((x1 - x2)**2 + (y1 - y2)**2)**0.5
xlen, ylen = trav_map.shape
g = nx.Graph()
for i in range(1, xlen):
for j in range(1, ylen):
if trav_map[i, j] > 0:
g.add_node((i, j))
if trav_map[i - 1, j] > 0:
g.add_edge((i - 1, j), (i, j))
if trav_map[i, j - 1] > 0:
g.add_edge((i, j - 1), (i, j))
largest_cc = max(nx.connected_components(g), key=len)
source_idx = np.random.randint(len(largest_cc))
node_list = list(largest_cc)
path = []
for i in range(10):
target_idx = np.random.randint(len(largest_cc))
source = node_list[source_idx]
target = node_list[target_idx]
path.extend(nx.astar_path(g, source, target, heuristic=dist))
source_idx = target_idx
path = np.array(path)
plt.figure(figsize=(12, 12))
plt.imshow(trav_map)
plt.scatter(path[:, 1], path[:, 0], s=1, c='r')
plt.show()
obj = Pedestrian()
ped_id = s.import_object(obj)
for object in ids:
p.setCollisionFilterPair(object, ped_id, -1, -1, 0)
y, x = scene.coord_to_pos(path[0][0], path[0][1])
prev_y = [y]
prev_x = [x]
for point in path[1:]:
y, x = scene.coord_to_pos(point[0], point[1])
s.step()
prev_y_mean = np.mean(prev_y)
prev_x_mean = np.mean(prev_x)
prev_y.append(y)
prev_x.append(x)
if len(prev_y) > 5:
prev_y.pop(0)
if len(prev_x) > 5:
prev_x.pop(0)
angle = np.arctan2(y - prev_y_mean, x - prev_x_mean)
direction = p.getQuaternionFromEuler([0, 0, angle])
obj.reset_position_orientation([x, y, 0.03], direction)

View File

@ -10,7 +10,7 @@ from gibson2.core.render.profiler import Profiler
config = parse_config('../configs/turtlebot_p2p_nav.yaml')
s = Simulator(mode='gui', resolution=512, render_to_tensor=False)
s = Simulator(mode='gui', image_width=512, image_height=512, render_to_tensor=False)
scene = BuildingScene('Rs')
s.import_scene(scene)
turtlebot = Turtlebot(config)

View File

@ -12,7 +12,7 @@ import random
config = parse_config('../configs/turtlebot_p2p_nav.yaml')
s = Simulator(mode='gui', resolution=512, render_to_tensor=False)
s = Simulator(mode='gui', image_width=512, image_height=512, render_to_tensor=False)
scene = BuildingScene('Ohoopee')
s.import_scene(scene)
turtlebot = Turtlebot(config)

View File

@ -5,7 +5,7 @@ currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentfram
parentdir = os.path.dirname(currentdir)
os.sys.path.insert(0, parentdir)
import pybullet_data
from gibson2.data.datasets import get_model_path
from gibson2.utils.assets_utils import get_model_path
from gibson2.utils.utils import l2_distance
import numpy as np

View File

@ -2,6 +2,7 @@ cmake_minimum_required(VERSION 2.8.12)
project(CppMeshRenderer)
set (USE_GLAD TRUE)
set (USE_CUDA TRUE)
set (USE_GLFW FALSE)
include_directories(glad)
@ -13,18 +14,22 @@ endif()
if (USE_CUDA)
add_definitions(-DUSE_CUDA)
find_package(OpenGL)
#OpenGL is still needed for cuda-gl interoperation
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")
if (USE_GLFW)
# 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")
endif()
if (USE_CUDA)
find_package(CUDA REQUIRED)
@ -35,22 +40,33 @@ else()
endif()
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_GLFW)
add_library(GLFWRendererContext MODULE glad/gl.cpp cpp/glfw_mesh_renderer.cpp)
endif()
if (USE_GLAD)
target_link_libraries(MeshRendererContext PRIVATE pybind11::module dl pthread)
target_link_libraries(GLFWRendererContext PRIVATE pybind11::module dl glfw ${GLFW_LIBRARIES})
if (USE_GLFW)
target_link_libraries(GLFWRendererContext PRIVATE pybind11::module dl glfw ${GLFW_LIBRARIES})
endif()
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})
if (USE_GLFW)
target_link_libraries(GLFWRendererContext PRIVATE pybind11::module dl glfw ${GLFW_LIBRARIES} ${OPENGL_LIBRARIES})
endif()
endif()
target_link_libraries(tinyobjloader PRIVATE pybind11::module)
set_target_properties(MeshRendererContext PROPERTIES PREFIX "${PYTHON_MODULE_PREFIX}"
SUFFIX "${PYTHON_MODULE_EXTENSION}")
if (USE_GLFW)
set_target_properties(GLFWRendererContext PROPERTIES PREFIX "${PYTHON_MODULE_PREFIX}"
SUFFIX "${PYTHON_MODULE_EXTENSION}")
endif()
set_target_properties(tinyobjloader PROPERTIES PREFIX "${PYTHON_MODULE_PREFIX}"
SUFFIX "${PYTHON_MODULE_EXTENSION}")

View File

@ -10,14 +10,13 @@ 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, GLFWRendererContext
from gibson2.core.render.mesh_renderer import MeshRendererContext
from gibson2.core.render.mesh_renderer.get_available_devices import get_available_devices
import gibson2.core.render.mesh_renderer as mesh_renderer
import pybullet as p
import gibson2
import os
from gibson2.core.render.mesh_renderer import tinyobjloader
import torch
class VisualObject(object):
"""
@ -307,7 +306,6 @@ class MeshRenderer(object):
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()

View File

@ -2,67 +2,72 @@ import cv2
import sys
import numpy as np
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
class MeshRendererG2G(MeshRenderer):
"""
Similar to MeshRenderer, but allows rendering to pytorch tensor, note that
pytorch installation is required.
"""
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):
self.image_tensor = torch.cuda.ByteTensor(height, width, 4).cuda()
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 = []
with torch.cuda.device(self.cuda_idx):
if 'rgb' in modes:
self.r.map_tensor(int(self.color_tex_rgb), int(self.width), int(self.height),
self.image_tensor.data_ptr())
results.append(self.image_tensor.clone())
if 'normal' in modes:
self.r.map_tensor(int(self.color_tex_normal), int(self.width), int(self.height),
self.normal_tensor.data_ptr())
results.append(self.normal_tensor.clone())
if 'seg' in modes:
self.r.map_tensor(int(self.color_tex_semantics), int(self.width), int(self.height),
self.seg_tensor.data_ptr())
results.append(self.seg_tensor.clone())
if '3d' in modes:
self.r.map_tensor_float(int(self.color_tex_3d), int(self.width), int(self.height),
self.pc_tensor.data_ptr())
results.append(self.pc_tensor.clone())
return results
def render(self, modes=('rgb', 'normal', 'seg', '3d'), hidden=()):
try:
import torch
class MeshRendererG2G(MeshRenderer):
"""
A function to render all the instances in the renderer and read the output from framebuffer into pytorch tensor.
:param modes: it should be a tuple consisting of a subset of ('rgb', 'normal', 'seg', '3d').
:param hidden: Hidden instances to skip. When rendering from a robot's perspective, it's own body can be
hidden
Similar to MeshRenderer, but allows rendering to pytorch tensor, note that
pytorch installation is required.
"""
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()
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):
self.image_tensor = torch.cuda.ByteTensor(height, width, 4).cuda()
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()
self.r.render_tensor_post()
if self.msaa:
self.r.blit_buffer(self.width, self.height, self.fbo_ms, self.fbo)
def readbuffer_to_tensor(self, modes=('rgb', 'normal', 'seg', '3d')):
results = []
with torch.cuda.device(self.cuda_idx):
if 'rgb' in modes:
self.r.map_tensor(int(self.color_tex_rgb), int(self.width), int(self.height),
self.image_tensor.data_ptr())
results.append(self.image_tensor.clone())
if 'normal' in modes:
self.r.map_tensor(int(self.color_tex_normal), int(self.width), int(self.height),
self.normal_tensor.data_ptr())
results.append(self.normal_tensor.clone())
if 'seg' in modes:
self.r.map_tensor(int(self.color_tex_semantics), int(self.width), int(self.height),
self.seg_tensor.data_ptr())
results.append(self.seg_tensor.clone())
if '3d' in modes:
self.r.map_tensor_float(int(self.color_tex_3d), int(self.width), int(self.height),
self.pc_tensor.data_ptr())
results.append(self.pc_tensor.clone())
return self.readbuffer_to_tensor(modes)
return results
def render(self, modes=('rgb', 'normal', 'seg', '3d'), hidden=()):
"""
A function to render all the instances in the renderer and read the output from framebuffer into pytorch tensor.
:param modes: it should be a tuple consisting of a subset of ('rgb', 'normal', 'seg', '3d').
:param hidden: Hidden instances to skip. When rendering from a robot's perspective, it's own body can be
hidden
"""
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()
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)
except:
print("torch is not available, falling back to rendering to memory(instead of tensor)")
MeshRendererG2G = MeshRenderer

View File

@ -55,11 +55,7 @@ def depth_loader(path):
return img
def get_model_path(model_id):
data_path = gibson2.dataset_path
assert (model_id in os.listdir(data_path)
) or model_id == 'stadium', "Model {} does not exist".format(model_id)
return os.path.join(data_path, model_id)
def get_item_fn(inds, select, root, loader, transform, off_3d, target_transform, depth_trans,

View File

@ -31,7 +31,7 @@ class Demo(object):
def run_demo(self):
config = parse_config(os.path.join(gibson2.assets_path,'turtlebot_p2p_nav_house.yaml'))
s = Simulator(mode='gui', resolution=700)
s = Simulator(mode='gui', image_width=700, image_height=700)
scene = BuildingScene('Rs')
s.import_scene(scene)
turtlebot = Turtlebot(config)

View File

@ -29,7 +29,7 @@ class DemoInteractive(object):
def run_demo(self):
config = parse_config(os.path.join(gibson2.assets_path,'turtlebot_p2p_nav_house.yaml'))
s = Simulator(mode='gui', resolution=700)
s = Simulator(mode='gui', image_width=700, image_height=700)
model_path = os.path.join(gibson2.dataset_path, 'Rs_interactive', 'rs_interactive.urdf')
scene = InteractiveBuildingScene(model_path)
s.import_scene(scene)

View File

@ -9,7 +9,6 @@ import argparse
from gibson2.learn.completion import CompletionNet, identity_init, Perceptual
import torch.nn as nn
import torch
from torchvision import datasets, transforms
from transforms3d.quaternions import quat2mat, qmult
import gym
import numpy as np

View File

@ -1,5 +1,12 @@
import gibson2
import os
def get_model_path(model_id):
data_path = gibson2.dataset_path
assert (model_id in os.listdir(data_path)
) or model_id == 'stadium', "Model {} does not exist".format(model_id)
return os.path.join(data_path, model_id)
def download_data():
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')

View File

@ -101,7 +101,7 @@ class PostInstallCommand(install):
setup(
name='gibson2',
version='0.0.2',
version='0.0.2b',
author='Stanford University',
zip_safe=False,
packages=find_packages(),