nbv_sim/active_grasp/controller.py

120 lines
3.4 KiB
Python
Raw Normal View History

2021-07-22 11:05:30 +02:00
from geometry_msgs.msg import PoseStamped
2021-07-06 14:00:04 +02:00
import numpy as np
import rospy
2021-07-22 11:05:30 +02:00
import time
2021-07-06 14:00:04 +02:00
2021-07-22 11:05:30 +02:00
from active_grasp.bbox import from_bbox_msg
2021-07-07 16:29:50 +02:00
from active_grasp.srv import Reset, ResetRequest
2021-07-22 11:05:30 +02:00
from robot_helpers.ros.conversions import to_pose_stamped_msg
from robot_helpers.ros.panda import PandaGripperClient
from robot_helpers.spatial import Rotation, Transform
2021-07-06 14:00:04 +02:00
class GraspController:
def __init__(self, policy):
self.policy = policy
2021-07-22 11:05:30 +02:00
self._reset_env = rospy.ServiceProxy("reset", Reset)
self._load_parameters()
self._init_robot_control()
2021-07-06 14:00:04 +02:00
2021-07-22 11:05:30 +02:00
def _load_parameters(self):
2021-07-06 14:00:04 +02:00
self.T_G_EE = Transform.from_list(rospy.get_param("~ee_grasp_offset")).inv()
2021-07-22 11:05:30 +02:00
def _init_robot_control(self):
self.target_pose_pub = rospy.Publisher("command", PoseStamped, queue_size=10)
self.gripper = PandaGripperClient()
def _send_cmd(self, pose):
msg = to_pose_stamped_msg(pose, "panda_link0")
self.target_pose_pub.publish(msg)
2021-07-06 14:00:04 +02:00
def run(self):
2021-07-22 11:05:30 +02:00
bbox = self._reset()
with Timer("search_time"):
grasp = self._search_grasp(bbox)
res = self._execute_grasp(grasp)
return self._collect_info(res)
def _reset(self):
res = self._reset_env(ResetRequest())
2021-07-07 16:29:50 +02:00
rospy.sleep(1.0) # wait for states to be updated
return from_bbox_msg(res.bbox)
2021-07-06 14:00:04 +02:00
2021-07-22 11:05:30 +02:00
def _search_grasp(self, bbox):
2021-07-07 15:08:32 +02:00
self.policy.activate(bbox)
2021-07-06 14:00:04 +02:00
r = rospy.Rate(self.policy.rate)
2021-07-22 11:05:30 +02:00
while True:
2021-07-06 14:00:04 +02:00
cmd = self.policy.update()
if self.policy.done:
break
2021-07-22 11:05:30 +02:00
self._send_cmd(cmd)
2021-07-06 14:00:04 +02:00
r.sleep()
return self.policy.best_grasp
2021-07-22 11:05:30 +02:00
def _execute_grasp(self, grasp):
2021-07-12 13:12:36 +02:00
if not grasp:
return "aborted"
2021-07-22 11:05:30 +02:00
T_B_G = self._postprocess(grasp)
2021-07-06 14:00:04 +02:00
self.gripper.move(0.08)
# Move to an initial pose offset.
2021-07-22 11:05:30 +02:00
self._send_cmd(T_B_G * Transform.translation([0, 0, -0.05]) * self.T_G_EE)
2021-07-06 14:00:04 +02:00
rospy.sleep(3.0)
# Approach grasp pose.
2021-07-22 11:05:30 +02:00
self._send_cmd(T_B_G * self.T_G_EE)
rospy.sleep(2.0)
2021-07-06 14:00:04 +02:00
# Close the fingers.
self.gripper.grasp()
# Lift the object.
target = Transform.translation([0, 0, 0.2]) * T_B_G * self.T_G_EE
2021-07-22 11:05:30 +02:00
self._send_cmd(target)
2021-07-06 14:00:04 +02:00
rospy.sleep(2.0)
# Check whether the object remains in the hand
2021-07-12 13:12:36 +02:00
success = self.gripper.read() > 0.005
return "succeeded" if success else "failed"
2021-07-06 14:00:04 +02:00
2021-07-22 11:05:30 +02:00
def _postprocess(self, T_B_G):
2021-07-06 14:00:04 +02:00
# Ensure that the camera is pointing forward.
rot = T_B_G.rotation
if rot.as_matrix()[:, 0][0] < 0:
T_B_G.rotation = rot * Rotation.from_euler("z", np.pi)
return T_B_G
2021-07-12 13:12:36 +02:00
2021-07-22 11:05:30 +02:00
def _collect_info(self, result):
2021-07-12 13:12:36 +02:00
points = [p.translation for p in self.policy.viewpoints]
d = np.sum([np.linalg.norm(p2 - p1) for p1, p2 in zip(points, points[1:])])
info = {
"result": result,
"viewpoint_count": len(points),
2021-07-22 11:05:30 +02:00
"distance": d,
2021-07-12 13:12:36 +02:00
}
info.update(Timer.timers)
return info
2021-07-22 11:05:30 +02:00
class Timer:
timers = dict()
def __init__(self, name):
self.name = name
def __enter__(self):
self.start()
return self
def __exit__(self, *exc_info):
self.stop()
def start(self):
self.tic = time.perf_counter()
def stop(self):
elapsed_time = time.perf_counter() - self.tic
self.timers[self.name] = elapsed_time