nbv_sim/policies.py

184 lines
5.8 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
import scipy.interpolate
2021-04-29 10:50:33 +02:00
from geometry_msgs.msg import Pose
from sensor_msgs.msg import Image, CameraInfo
2021-05-26 21:54:54 +02:00
import std_srvs.srv
2021-04-15 10:44:08 +02:00
2021-05-26 14:46:12 +02:00
from robot_tools.spatial import Rotation, Transform
from robot_tools.ros.conversions import *
2021-05-26 21:54:54 +02:00
from robot_tools.ros.panda import PandaGripperClient
2021-05-26 14:46:12 +02:00
from robot_tools.ros.tf import TransformTree
from robot_tools.perception import *
2021-04-29 10:50:33 +02:00
from vgn import vis
2021-05-05 11:18:43 +02:00
from vgn.detection import VGN, compute_grasps
2021-04-15 10:44:08 +02:00
2021-05-26 21:54:54 +02:00
def get_controller(name):
2021-04-29 10:50:33 +02:00
if name == "single-view":
return SingleViewBaseline()
elif name == "fixed-trajectory":
return FixedTrajectoryBaseline()
2021-05-26 14:46:12 +02:00
elif name == "mvp":
return MultiViewPicking()
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-05-26 21:54:54 +02:00
class BaseController:
2021-04-15 10:44:08 +02:00
def __init__(self):
2021-05-26 21:54:54 +02:00
self.frame_id = rospy.get_param("~frame_id")
self.length = rospy.get_param("~length")
2021-05-05 11:18:43 +02:00
2021-05-26 21:54:54 +02:00
self.cv_bridge = cv_bridge.CvBridge()
2021-05-05 11:41:10 +02:00
self.tf = TransformTree()
2021-05-26 21:54:54 +02:00
self.reset_client = rospy.ServiceProxy("/reset", std_srvs.srv.Trigger)
self.tsdf = UniformTSDFVolume(0.3, 40)
self.vgn = VGN(Path(rospy.get_param("vgn/model")))
self.setup_robot_connection()
self.setup_camera_connection()
self.lookup_transforms()
def setup_robot_connection(self):
self.base_frame_id = rospy.get_param("~base_frame_id")
self.ee_frame_id = rospy.get_param("~ee_frame_id")
self.ee_grasp_offset = Transform.from_list(rospy.get_param("~ee_grasp_offset"))
2021-05-26 14:46:12 +02:00
self.target_pose_pub = rospy.Publisher("/cmd", Pose, queue_size=10)
2021-05-26 21:54:54 +02:00
self.gripper = PandaGripperClient()
2021-04-29 10:50:33 +02:00
2021-05-26 21:54:54 +02:00
def setup_camera_connection(self):
2021-05-26 14:46:12 +02:00
self.cam_frame_id = rospy.get_param("~camera/frame_id")
info_topic = rospy.get_param("~camera/info_topic")
msg = rospy.wait_for_message(info_topic, CameraInfo, rospy.Duration(2.0))
2021-04-29 10:50:33 +02:00
self.intrinsic = from_camera_info_msg(msg)
2021-05-26 21:54:54 +02:00
depth_topic = rospy.get_param("~camera/depth_topic")
2021-05-05 11:41:10 +02:00
rospy.Subscriber(depth_topic, Image, self.sensor_cb, queue_size=1)
2021-04-29 10:50:33 +02:00
def sensor_cb(self, msg):
self.last_depth_img = self.cv_bridge.imgmsg_to_cv2(msg).astype(np.float32)
2021-05-05 11:41:10 +02:00
self.last_extrinsic = self.tf.lookup(
2021-05-26 21:54:54 +02:00
self.cam_frame_id,
self.frame_id,
msg.header.stamp,
rospy.Duration(0.1),
2021-04-29 10:50:33 +02:00
)
2021-05-26 21:54:54 +02:00
def lookup_transforms(self):
self.T_B_O = self.tf.lookup(self.base_frame_id, self.frame_id, rospy.Time.now())
2021-05-05 12:22:41 +02:00
2021-05-26 21:54:54 +02:00
def run(self):
self.reset()
self.explore()
self.execute_grasp()
2021-05-05 12:22:41 +02:00
2021-05-26 21:54:54 +02:00
def reset(self):
req = std_srvs.srv.TriggerRequest()
self.reset_client(req)
rospy.sleep(1.0) # wait for states to be updated
self.done = False
def explore(self):
r = rospy.Rate(self.rate)
while not self.done:
self.update()
r.sleep()
def update(self):
raise NotImplementedError
def execute_grasp(self):
if not self.best_grasp:
2021-05-26 14:46:12 +02:00
return
2021-05-26 21:54:54 +02:00
grasp = self.best_grasp
# Ensure that the camera is pointing forward.
2021-05-05 12:22:41 +02:00
rot = grasp.pose.rotation
2021-05-26 21:54:54 +02:00
if rot.as_matrix()[:, 0][0] < 0:
2021-05-05 12:22:41 +02:00
grasp.pose.rotation = rot * Rotation.from_euler("z", np.pi)
2021-05-26 21:54:54 +02:00
target = self.T_B_O * grasp.pose * self.ee_grasp_offset.inv()
self.gripper.move(0.08)
rospy.sleep(1.0) # TODO properly implement the simulated move server
self.target_pose_pub.publish(to_pose_msg(target))
rospy.sleep(2.0)
self.gripper.move(0.0)
rospy.sleep(1.0) # TODO
target.translation[2] += 0.3
self.target_pose_pub.publish(to_pose_msg(target))
rospy.sleep(2.0)
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]
grasps = compute_grasps(self.tsdf.voxel_size, out, score_fn)
vis.draw_grasps(grasps, 0.05)
return grasps[0] if len(grasps) > 0 else None
2021-05-05 12:22:41 +02:00
2021-04-15 10:44:08 +02:00
2021-05-26 21:54:54 +02:00
class SingleViewBaseline(BaseController):
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-05-26 21:54:54 +02:00
def reset(self):
super().reset()
2021-05-05 12:22:41 +02:00
def update(self):
self.tsdf.integrate(
self.last_depth_img,
self.intrinsic,
self.last_extrinsic,
)
cloud = self.tsdf.get_scene_cloud()
vis.draw_points(np.asarray(cloud.points))
2021-05-26 21:54:54 +02:00
self.best_grasp = self.predict_best_grasp()
2021-05-05 12:22:41 +02:00
self.done = True
2021-04-15 10:44:08 +02:00
2021-04-29 10:50:33 +02:00
2021-05-26 21:54:54 +02:00
class FixedTrajectoryBaseline(BaseController):
2021-04-15 10:44:08 +02:00
def __init__(self):
super().__init__()
2021-05-26 21:54:54 +02:00
self.rate = 10
2021-04-15 10:44:08 +02:00
self.duration = 4.0
self.radius = 0.1
self.m = scipy.interpolate.interp1d([0, self.duration], [np.pi, 3.0 * np.pi])
2021-05-26 21:54:54 +02:00
def reset(self):
super().reset()
2021-04-15 10:44:08 +02:00
self.tic = rospy.Time.now()
timeout = rospy.Duration(0.1)
2021-05-05 11:41:10 +02:00
x0 = self.tf.lookup(self.base_frame_id, self.ee_frame_id, self.tic, timeout)
2021-05-26 21:54:54 +02:00
self.center = np.r_[x0.translation[0] + self.radius, x0.translation[1:]]
2021-04-15 10:44:08 +02:00
self.target = x0
def update(self):
elapsed_time = (rospy.Time.now() - self.tic).to_sec()
if elapsed_time > self.duration:
2021-05-26 21:54:54 +02:00
self.best_grasp = self.predict_best_grasp()
2021-04-29 10:50:33 +02:00
self.done = True
2021-05-26 21:54:54 +02:00
else:
self.tsdf.integrate(
self.last_depth_img,
self.intrinsic,
self.last_extrinsic,
)
cloud = self.tsdf.get_scene_cloud()
vis.draw_points(np.asarray(cloud.points))
t = self.m(elapsed_time)
self.target.translation = (
self.center
+ np.r_[self.radius * np.cos(t), self.radius * np.sin(t), 0.0]
)
self.target_pose_pub.publish(to_pose_msg(self.target))
class MultiViewPicking(BaseController):
2021-05-26 14:46:12 +02:00
pass