nbv_sim/active_grasp/policy.py

153 lines
5.0 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-04-15 10:44:08 +02:00
2021-07-22 11:05:30 +02:00
class Policy:
2021-08-25 18:29:10 +02:00
def __init__(self, rate=5):
2021-08-03 18:11:30 +02:00
self.load_parameters()
self.init_visualizer()
def load_parameters(self):
2021-09-03 22:39:17 +02:00
self.base_frame = rospy.get_param("~base_frame_id")
2021-08-03 18:11:30 +02:00
self.task_frame = "task"
2021-09-11 20:49:55 +02:00
info_topic = rospy.get_param("~camera/info_topic")
2021-08-06 15:23:50 +02:00
msg = rospy.wait_for_message(info_topic, CameraInfo, rospy.Duration(2.0))
self.intrinsic = from_camera_info_msg(msg)
2021-09-11 20:49:55 +02:00
self.qual_threshold = rospy.get_param("vgn/qual_threshold")
2021-08-03 18:11:30 +02:00
def init_visualizer(self):
2021-08-25 14:57:43 +02:00
self.vis = Visualizer()
2021-07-07 15:08:32 +02:00
2021-09-11 20:49:55 +02:00
def activate(self, bbox, view_sphere):
2021-08-25 18:29:10 +02:00
self.vis.clear()
self.bbox = bbox
2021-09-11 20:49:55 +02:00
self.view_sphere = view_sphere
self.vis.bbox(self.base_frame, self.bbox)
2021-09-10 23:29:15 +02:00
self.calibrate_task_frame()
2021-08-25 18:29:10 +02:00
self.tsdf = UniformTSDFVolume(0.3, 40)
self.vgn = VGN(Path(rospy.get_param("vgn/model")))
2021-08-25 21:32:47 +02:00
self.views = []
2021-08-03 18:11:30 +02:00
self.best_grasp = None
2021-09-11 20:49:55 +02:00
self.x_d = None
2021-08-25 18:29:10 +02:00
self.done = False
2021-08-03 18:11:30 +02:00
2021-08-25 18:29:10 +02:00
def calibrate_task_frame(self):
self.T_base_task = Transform.translation(self.bbox.center - np.full(3, 0.15))
2021-08-25 18:29:10 +02:00
self.T_task_base = self.T_base_task.inv()
tf.broadcast(self.T_base_task, self.base_frame, self.task_frame)
rospy.sleep(0.5) # Wait for tf tree to be updated
self.vis.workspace(self.task_frame, 0.3)
2021-06-08 10:20:34 +02:00
def update(self, img, pose):
raise NotImplementedError
2021-09-03 22:39:17 +02:00
2021-08-25 18:29:10 +02:00
def sort_grasps(self, in_grasps):
2021-09-03 17:10:36 +02:00
# Transforms grasps into base frame, checks whether they lie on the target, and sorts by their score
2021-08-25 18:29:10 +02:00
grasps, scores = [], []
for grasp in in_grasps:
2021-08-10 18:52:03 +02:00
pose = self.T_base_task * grasp.pose
2021-09-10 23:29:15 +02:00
R, t = pose.rotation, pose.translation
# Filter out artifacts close to the support
if t[2] < self.bbox.min[2] + 0.04:
continue
2021-08-10 18:52:03 +02:00
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-25 18:29:10 +02:00
grasps.append(grasp)
scores.append(self.score_fn(grasp))
grasps, scores = np.asarray(grasps), np.asarray(scores)
indices = np.argsort(-scores)
return grasps[indices], scores[indices]
def score_fn(self, grasp):
return grasp.quality
2021-08-25 18:29:10 +02:00
class SingleViewPolicy(Policy):
2021-09-03 22:39:17 +02:00
def update(self, img, x):
2021-09-11 20:49:55 +02:00
linear, _ = compute_error(self.x_d, x)
2021-09-04 15:50:29 +02:00
if np.linalg.norm(linear) < 0.02:
2021-09-03 22:39:17 +02:00
self.views.append(x)
self.tsdf.integrate(img, self.intrinsic, x.inv() * self.T_base_task)
2021-08-25 18:29:10 +02:00
tsdf_grid, voxel_size = self.tsdf.get_grid(), self.tsdf.voxel_size
self.vis.scene_cloud(self.task_frame, self.tsdf.get_scene_cloud())
self.vis.map_cloud(self.task_frame, self.tsdf.get_map_cloud())
out = self.vgn.predict(tsdf_grid)
2021-09-10 23:29:15 +02:00
self.vis.quality(self.task_frame, voxel_size, out.qual, 0.5)
2021-08-25 18:29:10 +02:00
2021-09-03 22:39:17 +02:00
grasps = select_grid(voxel_size, out, threshold=self.qual_threshold)
2021-08-25 18:29:10 +02:00
grasps, scores = self.sort_grasps(grasps)
self.vis.grasps(self.base_frame, grasps, scores)
self.best_grasp = grasps[0] if len(grasps) > 0 else None
self.done = True
2021-06-08 10:20:34 +02:00
2021-04-15 10:44:08 +02:00
2021-08-25 21:32:47 +02:00
class MultiViewPolicy(Policy):
def activate(self, bbox, view_sphere):
super().activate(bbox, view_sphere)
self.T = 5 # Window size of grasp prediction history
self.qual_hist = np.zeros((self.T,) + (40,) * 3, np.float32)
2021-09-03 22:39:17 +02:00
def integrate(self, img, x):
self.views.append(x)
self.tsdf.integrate(img, self.intrinsic, x.inv() * self.T_base_task)
2021-08-25 21:32:47 +02:00
self.vis.scene_cloud(self.task_frame, self.tsdf.get_scene_cloud())
self.vis.map_cloud(self.task_frame, self.tsdf.get_map_cloud())
self.vis.path(self.base_frame, self.views)
tsdf_grid, voxel_size = self.tsdf.get_grid(), self.tsdf.voxel_size
out = self.vgn.predict(tsdf_grid)
2021-09-10 23:29:15 +02:00
self.vis.quality(self.task_frame, self.tsdf.voxel_size, out.qual, 0.5)
2021-08-25 21:32:47 +02:00
t = (len(self.views) - 1) % self.T
self.qual_hist[t, ...] = out.qual
2021-09-03 22:39:17 +02:00
grasps = select_grid(voxel_size, out, threshold=self.qual_threshold)
2021-08-25 21:32:47 +02:00
grasps, scores = self.sort_grasps(grasps)
if len(grasps) > 0:
self.best_grasp = grasps[0]
2021-09-03 11:50:14 +02:00
self.vis.best_grasp(self.base_frame, grasps[0], scores[0])
2021-08-25 21:32:47 +02:00
self.vis.grasps(self.base_frame, grasps, scores)
def compute_error(x_d, x):
linear = x_d.translation - x.translation
angular = (x_d.rotation * x.rotation.inv()).as_rotvec()
return linear, angular
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))