99 lines
3.6 KiB
Python
Raw Normal View History

2021-08-13 14:47:04 +02:00
import itertools
2021-08-11 18:10:06 +02:00
import numpy as np
2021-09-06 13:36:14 +02:00
import rospy
2021-08-11 18:10:06 +02:00
2021-09-11 20:49:55 +02:00
from .policy import MultiViewPolicy
2021-08-11 18:10:06 +02:00
2021-08-26 11:43:03 +02:00
class NextBestView(MultiViewPolicy):
2021-09-11 20:49:55 +02:00
def __init__(self):
super().__init__()
self.max_views = 40
def activate(self, bbox, view_sphere):
super().activate(bbox, view_sphere)
self.generate_view_candidates()
2021-09-11 20:49:55 +02:00
def generate_view_candidates(self):
thetas = np.arange(1, 4) * np.deg2rad(30)
phis = np.arange(1, 6) * np.deg2rad(60)
self.view_candidates = []
for theta, phi in itertools.product(thetas, phis):
view = self.view_sphere.get_view(theta, phi)
if self.view_sphere.is_feasible(view):
self.view_candidates.append(view)
2021-09-06 10:11:07 +02:00
def update(self, img, x):
2021-09-03 17:10:36 +02:00
if len(self.views) > self.max_views:
self.done = True
2021-08-26 11:43:03 +02:00
else:
2021-09-06 10:11:07 +02:00
self.integrate(img, x)
views = self.view_candidates
2021-09-11 20:49:55 +02:00
gains = [self.ig_fn(v) for v in views]
costs = [self.cost_fn(v) for v in views]
2021-09-03 17:10:36 +02:00
utilities = gains / np.sum(gains) - costs / np.sum(costs)
self.vis.views(self.base_frame, self.intrinsic, views, utilities)
i = np.argmax(utilities)
2021-09-11 20:49:55 +02:00
nbv, _ = views[i], gains[i]
self.x_d = nbv
2021-08-26 11:43:03 +02:00
def ig_fn(self, view, downsample=20):
2021-08-13 14:47:17 +02:00
fx = self.intrinsic.fx / downsample
fy = self.intrinsic.fy / downsample
cx = self.intrinsic.cx / downsample
cy = self.intrinsic.cy / downsample
2021-08-11 18:10:06 +02:00
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()
2021-08-18 10:40:10 +02:00
t_min = 0.1
2021-08-17 22:12:52 +02:00
t_max = corners[2].max() # TODO This bound might be a bit too short
2021-08-17 21:56:05 +02:00
t_step = 0.01
view = self.T_task_base * view # We'll work in the task frame from now on
2021-08-18 10:05:04 +02:00
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
2021-08-18 10:40:10 +02:00
voxel_indices = []
for u in range(u_min, u_max):
for v in range(v_min, v_max):
2021-08-17 21:56:05 +02:00
origin = view.translation
direction = np.r_[(u - cx) / fx, (v - cy) / fy, 1.0]
2021-08-17 21:56:05 +02:00
direction = view.rotation.apply(direction / np.linalg.norm(direction))
2021-08-25 14:57:43 +02:00
# self.vis.rays(self.task_frame, origin, [direction])
2021-08-18 10:40:10 +02:00
# rospy.sleep(0.01)
2021-08-18 10:05:04 +02:00
t, tsdf_prev = t_min, -1.0
2021-08-17 21:56:05 +02:00
while t < t_max:
p = origin + t * direction
t += t_step
2021-08-25 14:57:43 +02:00
# self.vis.point(self.task_frame, p)
2021-08-18 10:40:10 +02:00
# rospy.sleep(0.01)
2021-08-18 10:05:04 +02:00
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
2021-08-18 10:40:10 +02:00
# TODO check whether the voxel lies within the bounding box ?
voxel_indices.append(index)
2021-08-18 10:05:04 +02:00
tsdf_prev = tsdf
2021-08-18 10:40:10 +02:00
# 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
2021-08-11 18:10:06 +02:00
2021-08-26 11:43:03 +02:00
def cost_fn(self, view):
2021-08-11 18:10:06 +02:00
return 1.0