import itertools import numpy as np import rospy from .policy import BasePolicy from vgn.utils import look_at, spherical_to_cartesian class NextBestView(BasePolicy): def __init__(self, rate, filter_grasps): super().__init__(rate, filter_grasps) self.max_viewpoints = 20 self.min_gain = 10.0 def activate(self, bbox): super().activate(bbox) def update(self, img, extrinsic): # Integrate latest measurement self.integrate_img(img, extrinsic) # Generate viewpoints views = self.generate_viewpoints() # Evaluate viewpoints gains = [self.compute_ig(v) for v in views] costs = [self.compute_cost(v) for v in views] utilities = gains / np.sum(gains) - costs / np.sum(costs) # Visualize self.visualizer.views(self.base_frame, self.intrinsic, views, utilities) # Determine next-best-view i = np.argmax(utilities) nbv, g = views[i], gains[i] if self.check_done(g): self.best_grasp = self.compute_best_grasp() self.done = True return return nbv.inv() # the controller expects T_cam_base def generate_viewpoints(self): r, h = 0.14, 0.2 thetas = np.arange(1, 4) * np.deg2rad(30) phis = np.arange(1, 6) * np.deg2rad(60) views = [] for theta, phi in itertools.product(thetas, phis): eye = self.center + np.r_[0, 0, h] + spherical_to_cartesian(r, theta, phi) target = self.center up = np.r_[1.0, 0.0, 0.0] views.append(look_at(eye, target, up).inv()) return views def compute_ig(self, view, downsample=20): fx = self.intrinsic.fx / downsample fy = self.intrinsic.fy / downsample cx = self.intrinsic.cx / downsample cy = self.intrinsic.cy / downsample T_cam_base = view.inv() corners = np.array([T_cam_base.apply(p) for p in self.bbox.corners]).T u = (fx * corners[0] / corners[2] + cx).round().astype(int) v = (fy * corners[1] / corners[2] + cy).round().astype(int) u_min, u_max = u.min(), u.max() v_min, v_max = v.min(), v.max() t_min = 0.1 t_max = corners[2].max() # TODO This bound might be a bit too short t_step = 0.01 view = self.T_task_base * view # We'll work in the task frame from now on tsdf_grid, voxel_size = self.tsdf.get_grid(), self.tsdf.voxel_size def get_voxel_at(p): index = (p / voxel_size).astype(int) return index if (index >= 0).all() and (index < 40).all() else None voxel_indices = [] for u in range(u_min, u_max): for v in range(v_min, v_max): origin = view.translation direction = np.r_[(u - cx) / fx, (v - cy) / fy, 1.0] direction = view.rotation.apply(direction / np.linalg.norm(direction)) # self.visualizer.rays(self.task_frame, origin, [direction]) # rospy.sleep(0.01) t, tsdf_prev = t_min, -1.0 while t < t_max: p = origin + t * direction t += t_step # self.visualizer.point(self.task_frame, p) # rospy.sleep(0.01) index = get_voxel_at(p) if index is not None: i, j, k = index tsdf = -1 + 2 * tsdf_grid[i, j, k] # Open3D maps tsdf to [0,1] if tsdf * tsdf_prev < 0 and tsdf_prev > -1: # Crossed a surface break # TODO check whether the voxel lies within the bounding box ? voxel_indices.append(index) tsdf_prev = tsdf # Count rear side voxels i, j, k = np.unique(voxel_indices, axis=0).T tsdfs = tsdf_grid[i, j, k] ig = np.logical_and(tsdfs > 0.0, tsdfs < 0.5).sum() return ig def compute_cost(self, view): return 1.0 def check_done(self, gain): return len(self.viewpoints) > self.max_viewpoints or gain < self.min_gain