nbv_sim/active_grasp/policy.py

101 lines
3.2 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 *
2021-05-05 11:18:43 +02:00
from vgn.detection import VGN, compute_grasps
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):
2021-08-06 15:23:50 +02:00
def __init__(self, rate=5):
self.rate = rate
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")))
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
# Define the VGN task frame s.t. the bounding box is in its center
self.center = 0.5 * (bbox.min + bbox.max)
self.T_base_task = Transform.translation(self.center - np.full(3, 0.15))
tf.broadcast(self.T_base_task, self.base_frame, self.task_frame)
rospy.sleep(0.1) # wait for the transform to be published
2021-07-07 15:08:32 +02:00
self.tsdf = UniformTSDFVolume(0.3, 40)
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)
self.visualizer.scene_cloud(self.task_frame, self.tsdf.get_scene_cloud())
2021-07-22 11:05:30 +02:00
self.visualizer.path(self.viewpoints)
2021-06-08 10:20:34 +02:00
2021-08-06 15:23:50 +02:00
def compute_best_grasp(self):
return self.predict_best_grasp()
2021-08-03 18:11:30 +02:00
def predict_best_grasp(self):
2021-07-06 14:00:04 +02:00
tsdf_grid = self.tsdf.get_grid()
out = self.vgn.predict(tsdf_grid)
score_fn = lambda g: g.pose.translation[2]
2021-07-07 15:08:32 +02:00
grasps = compute_grasps(self.tsdf.voxel_size, out, score_fn, max_filter_size=3)
2021-08-03 18:11:30 +02:00
grasps = self.transform_grasps_to_base_frame(grasps)
grasps = self.select_grasps_on_target_object(grasps)
return grasps[0] if len(grasps) > 0 else None
def transform_grasps_to_base_frame(self, grasps):
for grasp in grasps:
grasp.pose = self.T_base_task * grasp.pose
return grasps
2021-06-08 10:20:34 +02:00
2021-08-03 18:11:30 +02:00
def select_grasps_on_target_object(self, grasps):
2021-07-22 11:05:30 +02:00
result = []
2021-08-03 18:11:30 +02:00
for grasp in grasps:
tip = grasp.pose.rotation.apply([0, 0, 0.05]) + grasp.pose.translation
2021-07-22 11:05:30 +02:00
if self.bbox.is_inside(tip):
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))