This commit is contained in:
Michel Breyer 2021-11-10 12:15:33 +01:00
parent 5f9c52bc19
commit 0ac5ca20aa
2 changed files with 10 additions and 3 deletions

View File

@ -10,6 +10,7 @@ from robot_helpers.spatial import Rotation
from vgn.perception import UniformTSDFVolume from vgn.perception import UniformTSDFVolume
from vgn.utils import find_urdfs, load_cfg, view_on_sphere from vgn.utils import find_urdfs, load_cfg, view_on_sphere
from vgn.detection import VGN, select_local_maxima from vgn.detection import VGN, select_local_maxima
import vgn.visualizer as vis
rospack = rospkg.RosPack() rospack = rospkg.RosPack()
pkg_root = Path(rospack.get_path("active_grasp")) pkg_root = Path(rospack.get_path("active_grasp"))
@ -94,7 +95,7 @@ class Simulation:
# First, reconstruct the scene from many views # First, reconstruct the scene from many views
tsdf = UniformTSDFVolume(self.scene.length, 40) tsdf = UniformTSDFVolume(self.scene.length, 40)
r = 2.0 * self.scene.length r = 2.0 * self.scene.length
theta = np.pi / 6.0 theta = np.pi / 4.0
phis = np.linspace(0.0, 2.0 * np.pi, 5) phis = np.linspace(0.0, 2.0 * np.pi, 5)
for view in [view_on_sphere(center, r, theta, phi) for phi in phis]: for view in [view_on_sphere(center, r, theta, phi) for phi in phis]:
depth_img = self.camera.get_image(view)[1] depth_img = self.camera.get_image(view)[1]
@ -103,7 +104,12 @@ class Simulation:
# Then check whether VGN can find any grasps on the target # Then check whether VGN can find any grasps on the target
out = self.vgn.predict(tsdf_grid) out = self.vgn.predict(tsdf_grid)
grasps, _ = select_local_maxima(voxel_size, out, threshold=0.9) grasps, qualities = select_local_maxima(voxel_size, out, threshold=0.9)
# vis.scene_cloud(voxel_size, tsdf.get_scene_cloud())
# vis.grasps(grasps, qualities, 0.05)
# vis.show()
for grasp in grasps: for grasp in grasps:
pose = origin * grasp.pose pose = origin * grasp.pose
tip = pose.rotation.apply([0, 0, 0.05]) + pose.translation tip = pose.rotation.apply([0, 0, 0.05]) + pose.translation

View File

@ -6,7 +6,8 @@ def main():
scene_id = "random" scene_id = "random"
vgn_path = "../vgn/assets/models/vgn_conv.pth" vgn_path = "../vgn/assets/models/vgn_conv.pth"
sim = Simulation(gui, scene_id, vgn_path) sim = Simulation(gui, scene_id, vgn_path)
bbox = sim.reset() while True:
sim.reset()
if __name__ == "__main__": if __name__ == "__main__":