nbv_sim/policies.py

167 lines
5.4 KiB
Python
Raw Normal View History

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-07 15:08:32 +02:00
from rospy import Publisher
2021-07-07 10:16:12 +02:00
import sensor_msgs.msg
2021-06-08 10:20:34 +02:00
from visualization_msgs.msg import Marker, MarkerArray
2021-07-07 10:16:12 +02:00
from robot_utils.perception import Image
2021-06-08 10:20:34 +02:00
from robot_utils.ros import tf
2021-07-06 14:00:04 +02:00
from robot_utils.ros.conversions import *
2021-06-08 10:20:34 +02:00
from robot_utils.ros.rviz import *
2021-07-06 14:00:04 +02:00
from robot_utils.spatial import Transform
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-06 14:00:04 +02:00
def get_policy(name):
2021-04-29 10:50:33 +02:00
if name == "single-view":
return SingleViewBaseline()
2021-04-26 10:45:00 +02:00
else:
raise ValueError("{} policy does not exist.".format(name))
2021-04-15 10:44:08 +02:00
2021-07-06 14:00:04 +02:00
class BasePolicy:
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-05-26 21:54:54 +02:00
2021-07-06 14:00:04 +02:00
self.load_parameters()
self.lookup_transforms()
self.connect_to_camera()
self.connect_to_rviz()
2021-05-26 21:54:54 +02:00
2021-07-06 14:00:04 +02:00
def load_parameters(self):
2021-06-08 10:20:34 +02:00
self.base_frame = rospy.get_param("~base_frame_id")
2021-07-06 14:00:04 +02:00
self.task_frame = rospy.get_param("~frame_id")
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")
def lookup_transforms(self):
tf._init_listener()
rospy.sleep(1.0) # wait to receive transforms
self.T_B_task = tf.lookup(self.base_frame, self.task_frame)
def connect_to_camera(self):
2021-07-07 10:16:12 +02:00
msg = rospy.wait_for_message(
self.info_topic, sensor_msgs.msg.CameraInfo, rospy.Duration(2.0)
)
2021-06-08 10:20:34 +02:00
self.intrinsic = from_camera_info_msg(msg)
2021-07-07 10:16:12 +02:00
rospy.Subscriber(
self.depth_topic, sensor_msgs.msg.Image, self.sensor_cb, queue_size=1
)
2021-06-08 10:20:34 +02:00
2021-07-06 14:00:04 +02:00
def sensor_cb(self, msg):
2021-07-07 10:16:12 +02:00
self.img = Image(depth=self.cv_bridge.imgmsg_to_cv2(msg).astype(np.float32))
2021-07-06 14:00:04 +02:00
self.extrinsic = tf.lookup(
self.cam_frame,
self.task_frame,
2021-06-08 10:20:34 +02:00
msg.header.stamp,
2021-07-06 14:00:04 +02:00
rospy.Duration(0.2),
2021-06-08 10:20:34 +02:00
)
2021-07-06 14:00:04 +02:00
def connect_to_rviz(self):
2021-07-07 15:08:32 +02:00
self.bbox_pub = Publisher("bbox", Marker, queue_size=1, latch=True)
self.cloud_pub = Publisher("cloud", PointCloud2, queue_size=1, latch=True)
self.path_pub = Publisher("path", MarkerArray, queue_size=1, latch=True)
self.grasps_pub = Publisher("grasps", MarkerArray, queue_size=1, latch=True)
def activate(self, bbox):
self.clear_grasps()
self.bbox = bbox
self.draw_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-06-08 10:20:34 +02:00
2021-07-06 14:00:04 +02:00
def update(self):
raise NotImplementedError
2021-06-08 10:20:34 +02:00
2021-07-06 14:00:04 +02:00
def integrate_latest_image(self):
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-06-08 10:20:34 +02:00
2021-07-06 14:00:04 +02:00
def predict_best_grasp(self):
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)
grasps = self.filter_grasps_on_target_object(grasps)
self.draw_grasps(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-07 15:08:32 +02:00
def filter_grasps_on_target_object(self, grasps):
return [
g
for g in grasps
if self.bbox.is_inside(
g.pose.rotation.apply([0, 0, 0.05]) + g.pose.translation
)
]
def clear_grasps(self):
self.grasps_pub.publish(DELETE_MARKER_ARRAY_MSG)
def draw_bbox(self):
pose = Transform.translation((self.bbox.min + self.bbox.max) / 2.0)
scale = self.bbox.max - self.bbox.min
color = np.r_[0.8, 0.2, 0.2, 0.6]
msg = create_marker(Marker.CUBE, self.task_frame, pose, scale, color)
self.bbox_pub.publish(msg)
2021-07-06 14:00:04 +02:00
def draw_scene_cloud(self):
cloud = self.tsdf.get_scene_cloud()
2021-07-07 15:08:32 +02:00
msg = to_cloud_msg(self.task_frame, np.asarray(cloud.points))
self.cloud_pub.publish(msg)
def draw_grasps(self, grasps):
msg = create_grasp_marker_array(self.task_frame, grasps, self.finger_depth)
self.grasps_pub.publish(msg)
2021-06-08 10:20:34 +02:00
2021-07-06 14:00:04 +02:00
def draw_camera_path(self):
2021-06-08 10:20:34 +02:00
identity = Transform.identity()
color = np.r_[31, 119, 180] / 255.0
# Spheres for each viewpoint
scale = 0.01 * np.ones(3)
2021-07-06 14:00:04 +02:00
spheres = create_marker(
Marker.SPHERE_LIST, self.task_frame, identity, scale, color
)
2021-06-08 10:20:34 +02:00
spheres.id = 0
spheres.points = [to_point_msg(p.translation) for p in self.viewpoints]
# Line strip connecting viewpoints
scale = [0.005, 0.0, 0.0]
2021-07-06 14:00:04 +02:00
lines = create_marker(
Marker.LINE_STRIP, self.task_frame, identity, scale, color
)
2021-06-08 10:20:34 +02:00
lines.id = 1
lines.points = [to_point_msg(p.translation) for p in self.viewpoints]
2021-07-06 14:00:04 +02:00
self.path_pub.publish(MarkerArray([spheres, lines]))
2021-06-08 10:20:34 +02:00
2021-04-15 10:44:08 +02:00
2021-07-06 14:00:04 +02:00
class SingleViewBaseline(BasePolicy):
2021-06-08 10:20:34 +02:00
"""
2021-07-06 14:00:04 +02:00
Process a single image from the initial viewpoint.
2021-06-08 10:20:34 +02:00
"""
2021-05-26 21:54:54 +02:00
def __init__(self):
2021-05-05 12:22:41 +02:00
super().__init__()
2021-05-26 21:54:54 +02:00
self.rate = 1
2021-05-05 12:22:41 +02:00
2021-07-06 14:00:04 +02:00
def update(self):
self.integrate_latest_image()
self.draw_scene_cloud()
self.best_grasp = self.predict_best_grasp()
2021-05-05 12:22:41 +02:00
self.done = True