nbv_sim/active_grasp/policy.py

142 lines
4.8 KiB
Python
Raw Normal View History

2021-04-15 10:44:08 +02:00
import numpy as np
2021-08-06 15:23:50 +02:00
from sensor_msgs.msg import CameraInfo
2021-05-26 14:46:12 +02:00
from pathlib import Path
2021-04-15 10:44:08 +02:00
import rospy
2021-07-22 11:05:30 +02:00
from .visualization import Visualizer
from robot_helpers.ros import tf
from robot_helpers.ros.conversions import *
from vgn.detection import *
2021-07-06 14:00:04 +02:00
from vgn.perception import UniformTSDFVolume
2021-07-07 15:08:32 +02:00
from vgn.utils import *
2021-04-15 10:44:08 +02:00
2021-07-22 11:05:30 +02:00
class Policy:
def activate(self, bbox):
raise NotImplementedError
2021-08-03 18:11:30 +02:00
def update(self, img, extrinsic):
2021-07-22 11:05:30 +02:00
raise NotImplementedError
class BasePolicy(Policy):
def __init__(self, rate=5, filter_grasps=False):
2021-08-06 15:23:50 +02:00
self.rate = rate
self.filter_grasps = filter_grasps
2021-08-03 18:11:30 +02:00
self.load_parameters()
self.init_visualizer()
def load_parameters(self):
self.base_frame = rospy.get_param("active_grasp/base_frame_id")
self.task_frame = "task"
2021-08-06 15:23:50 +02:00
info_topic = rospy.get_param("active_grasp/camera/info_topic")
msg = rospy.wait_for_message(info_topic, CameraInfo, rospy.Duration(2.0))
self.intrinsic = from_camera_info_msg(msg)
2021-08-03 18:11:30 +02:00
self.vgn = VGN(Path(rospy.get_param("vgn/model")))
2021-08-10 18:52:03 +02:00
self.score_fn = lambda g: g.pose.translation[2] # TODO
2021-08-03 18:11:30 +02:00
def init_visualizer(self):
self.visualizer = Visualizer(self.base_frame)
2021-07-07 15:08:32 +02:00
def activate(self, bbox):
self.bbox = bbox
2021-08-03 18:11:30 +02:00
self.center = 0.5 * (bbox.min + bbox.max)
self.T_base_task = Transform.translation(self.center - np.full(3, 0.15))
2021-08-16 17:38:17 +02:00
self.T_task_base = self.T_base_task.inv()
2021-08-03 18:11:30 +02:00
tf.broadcast(self.T_base_task, self.base_frame, self.task_frame)
2021-08-10 18:52:03 +02:00
rospy.sleep(1.0) # wait for the transform to be published
2021-08-03 18:11:30 +02:00
2021-08-10 18:52:03 +02:00
N, self.T = 40, 10
grid_shape = (N,) * 3
self.tsdf = UniformTSDFVolume(0.3, N)
self.qual_hist = np.zeros((self.T,) + grid_shape, np.float32)
self.rot_hist = np.zeros((self.T, 4) + grid_shape, np.float32)
self.width_hist = np.zeros((self.T,) + grid_shape, np.float32)
2021-07-06 14:00:04 +02:00
self.viewpoints = []
self.done = False
2021-08-03 18:11:30 +02:00
self.best_grasp = None
2021-07-22 11:05:30 +02:00
self.visualizer.clear()
self.visualizer.bbox(bbox)
2021-06-08 10:20:34 +02:00
2021-08-03 18:11:30 +02:00
def integrate_img(self, img, extrinsic):
self.viewpoints.append(extrinsic.inv())
self.tsdf.integrate(img, self.intrinsic, extrinsic * self.T_base_task)
2021-06-08 10:20:34 +02:00
if self.filter_grasps:
2021-08-10 18:52:03 +02:00
out = self.vgn.predict(self.tsdf.get_grid())
t = (len(self.viewpoints) - 1) % self.T
self.qual_hist[t, ...] = out.qual
self.rot_hist[t, ...] = out.rot
self.width_hist[t, ...] = out.width
2021-08-06 15:23:50 +02:00
2021-08-10 18:52:03 +02:00
mean_qual = self.compute_mean_quality()
self.visualizer.quality(self.task_frame, self.tsdf.voxel_size, mean_qual)
self.visualizer.scene_cloud(self.task_frame, self.tsdf.get_scene_cloud())
self.visualizer.path(self.viewpoints)
def compute_best_grasp(self):
if self.filter_grasps:
2021-08-10 18:52:03 +02:00
qual = self.compute_mean_quality()
index_list = select_local_maxima(qual, 0.9, 3)
grasps = [g for i in index_list if (g := self.select_mean_at(i))]
else:
2021-08-10 18:52:03 +02:00
out = self.vgn.predict(self.tsdf.get_grid())
qual = out.qual
index_list = select_local_maxima(qual, 0.9, 3)
grasps = [select_at(out, i) for i in index_list]
grasps = [from_voxel_coordinates(g, self.tsdf.voxel_size) for g in grasps]
2021-08-10 18:52:03 +02:00
grasps = self.transform_and_reject(grasps)
grasps = sort_grasps(grasps, self.score_fn)
2021-08-10 18:52:03 +02:00
self.visualizer.quality(self.task_frame, self.tsdf.voxel_size, qual)
self.visualizer.grasps(grasps)
2021-08-03 18:11:30 +02:00
2021-08-10 18:52:03 +02:00
return grasps[0] if len(grasps) > 0 else None
2021-06-08 10:20:34 +02:00
2021-08-10 18:52:03 +02:00
def compute_mean_quality(self):
qual = np.mean(self.qual_hist, axis=0, where=self.qual_hist > 0.0)
return np.nan_to_num(qual, copy=False) # mean of empty slices returns nan
def select_mean_at(self, index):
i, j, k = index
ts = np.flatnonzero(self.qual_hist[:, i, j, k])
if len(ts) < 3:
return
ori = Rotation.from_quat([self.rot_hist[t, :, i, j, k] for t in ts])
pos = np.array([i, j, k], dtype=np.float64)
width = self.width_hist[ts, i, j, k].mean()
qual = self.qual_hist[ts, i, j, k].mean()
return Grasp(Transform(ori.mean(), pos), width, qual)
def transform_and_reject(self, grasps):
2021-07-22 11:05:30 +02:00
result = []
2021-08-03 18:11:30 +02:00
for grasp in grasps:
2021-08-10 18:52:03 +02:00
pose = self.T_base_task * grasp.pose
tip = pose.rotation.apply([0, 0, 0.05]) + pose.translation
2021-07-22 11:05:30 +02:00
if self.bbox.is_inside(tip):
2021-08-10 18:52:03 +02:00
grasp.pose = pose
2021-08-03 18:11:30 +02:00
result.append(grasp)
2021-07-22 11:05:30 +02:00
return result
2021-06-08 10:20:34 +02:00
2021-04-15 10:44:08 +02:00
2021-07-07 17:46:11 +02:00
registry = {}
2021-06-08 10:20:34 +02:00
2021-07-07 17:46:11 +02:00
def register(id, cls):
global registry
registry[id] = cls
2021-08-03 18:11:30 +02:00
def make(id, *args, **kwargs):
2021-07-07 17:46:11 +02:00
if id in registry:
2021-08-03 18:11:30 +02:00
return registry[id](*args, **kwargs)
2021-07-07 17:46:11 +02:00
else:
raise ValueError("{} policy does not exist.".format(id))