2021-04-29 10:50:33 +02:00
|
|
|
import cv_bridge
|
2021-04-15 10:44:08 +02:00
|
|
|
import numpy as np
|
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 sensor_msgs.msg import CameraInfo, Image, PointCloud2
|
|
|
|
|
|
|
|
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
|
|
|
|
|
|
|
|
def update(self):
|
|
|
|
raise NotImplementedError
|
|
|
|
|
|
|
|
|
|
|
|
class BasePolicy(Policy):
|
2021-04-15 10:44:08 +02:00
|
|
|
def __init__(self):
|
2021-05-26 21:54:54 +02:00
|
|
|
self.cv_bridge = cv_bridge.CvBridge()
|
|
|
|
self.vgn = VGN(Path(rospy.get_param("vgn/model")))
|
2021-07-07 15:08:32 +02:00
|
|
|
self.finger_depth = 0.05
|
2021-07-07 17:46:11 +02:00
|
|
|
self.rate = 5
|
2021-07-22 11:05:30 +02:00
|
|
|
self._load_parameters()
|
|
|
|
self._lookup_transforms()
|
|
|
|
self._init_camera_stream()
|
|
|
|
self._init_publishers()
|
|
|
|
self._init_visualizer()
|
2021-07-07 16:29:50 +02:00
|
|
|
|
2021-07-22 11:05:30 +02:00
|
|
|
def _load_parameters(self):
|
2021-07-06 14:00:04 +02:00
|
|
|
self.task_frame = rospy.get_param("~frame_id")
|
2021-07-07 17:46:11 +02:00
|
|
|
self.base_frame = rospy.get_param("~base_frame_id")
|
|
|
|
self.ee_frame = rospy.get_param("~ee_frame_id")
|
2021-07-06 14:00:04 +02:00
|
|
|
self.cam_frame = rospy.get_param("~camera/frame_id")
|
|
|
|
self.info_topic = rospy.get_param("~camera/info_topic")
|
|
|
|
self.depth_topic = rospy.get_param("~camera/depth_topic")
|
|
|
|
|
2021-07-22 11:05:30 +02:00
|
|
|
def _lookup_transforms(self):
|
2021-07-06 14:00:04 +02:00
|
|
|
self.T_B_task = tf.lookup(self.base_frame, self.task_frame)
|
2021-07-07 17:46:11 +02:00
|
|
|
self.T_EE_cam = tf.lookup(self.ee_frame, self.cam_frame)
|
2021-07-06 14:00:04 +02:00
|
|
|
|
2021-07-22 11:05:30 +02:00
|
|
|
def _init_camera_stream(self):
|
|
|
|
msg = rospy.wait_for_message(self.info_topic, CameraInfo, rospy.Duration(2.0))
|
2021-06-08 10:20:34 +02:00
|
|
|
self.intrinsic = from_camera_info_msg(msg)
|
2021-07-22 11:05:30 +02:00
|
|
|
rospy.Subscriber(self.depth_topic, Image, self._sensor_cb, queue_size=1)
|
2021-06-08 10:20:34 +02:00
|
|
|
|
2021-07-22 11:05:30 +02:00
|
|
|
def _sensor_cb(self, msg):
|
|
|
|
self.img = self.cv_bridge.imgmsg_to_cv2(msg).astype(np.float32)
|
|
|
|
self.extrinsic = tf.lookup(self.cam_frame, self.task_frame, msg.header.stamp)
|
|
|
|
|
|
|
|
def _init_publishers(self):
|
|
|
|
self.scene_cloud_pub = rospy.Publisher("scene_cloud", PointCloud2, queue_size=1)
|
2021-06-08 10:20:34 +02:00
|
|
|
|
2021-07-22 11:05:30 +02:00
|
|
|
def _init_visualizer(self):
|
|
|
|
self.visualizer = Visualizer(self.task_frame)
|
2021-07-07 15:08:32 +02:00
|
|
|
|
|
|
|
def activate(self, bbox):
|
|
|
|
self.bbox = bbox
|
|
|
|
self.tsdf = UniformTSDFVolume(0.3, 40)
|
2021-07-06 14:00:04 +02:00
|
|
|
self.viewpoints = []
|
|
|
|
self.done = False
|
|
|
|
self.best_grasp = None # grasp pose defined w.r.t. the robot's base frame
|
2021-07-22 11:05:30 +02:00
|
|
|
self.visualizer.clear()
|
|
|
|
self.visualizer.bbox(bbox)
|
2021-06-08 10:20:34 +02:00
|
|
|
|
2021-07-22 11:05:30 +02:00
|
|
|
def _integrate_latest_image(self):
|
2021-07-06 14:00:04 +02:00
|
|
|
self.viewpoints.append(self.extrinsic.inv())
|
|
|
|
self.tsdf.integrate(
|
2021-07-07 10:16:12 +02:00
|
|
|
self.img,
|
2021-07-06 14:00:04 +02:00
|
|
|
self.intrinsic,
|
|
|
|
self.extrinsic,
|
|
|
|
)
|
2021-07-22 11:05:30 +02:00
|
|
|
self._publish_scene_cloud()
|
|
|
|
self.visualizer.path(self.viewpoints)
|
2021-06-08 10:20:34 +02:00
|
|
|
|
2021-07-22 11:05:30 +02:00
|
|
|
def _publish_scene_cloud(self):
|
|
|
|
cloud = self.tsdf.get_scene_cloud()
|
|
|
|
msg = to_cloud_msg(self.task_frame, np.asarray(cloud.points))
|
|
|
|
self.scene_cloud_pub.publish(msg)
|
|
|
|
|
|
|
|
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-07-22 11:05:30 +02:00
|
|
|
grasps = self._select_grasps_on_target_object(grasps)
|
2021-07-06 14:00:04 +02:00
|
|
|
return self.T_B_task * grasps[0].pose if len(grasps) > 0 else None
|
2021-06-08 10:20:34 +02:00
|
|
|
|
2021-07-22 11:05:30 +02:00
|
|
|
def _select_grasps_on_target_object(self, grasps):
|
|
|
|
result = []
|
|
|
|
for g in grasps:
|
|
|
|
tip = g.pose.rotation.apply([0, 0, 0.05]) + g.pose.translation
|
|
|
|
if self.bbox.is_inside(tip):
|
|
|
|
result.append(g)
|
|
|
|
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
|
|
|
|
|
|
|
|
|
|
|
|
def make(id):
|
|
|
|
if id in registry:
|
|
|
|
return registry[id]()
|
|
|
|
else:
|
|
|
|
raise ValueError("{} policy does not exist.".format(id))
|