Update transform interface
This commit is contained in:
parent
d372f9b82c
commit
7f111252d0
@ -81,7 +81,7 @@ class HwNode:
|
|||||||
def publish_table_co(self, event):
|
def publish_table_co(self, event):
|
||||||
msg = geometry_msgs.msg.PoseStamped()
|
msg = geometry_msgs.msg.PoseStamped()
|
||||||
msg.header.frame_id = "panda_link0"
|
msg.header.frame_id = "panda_link0"
|
||||||
msg.pose = to_pose_msg(self.T_base_roi * Transform.t([0.15, 0.15, 0.005]))
|
msg.pose = to_pose_msg(self.T_base_roi * Transform.t_[0.15, 0.15, 0.005])
|
||||||
self.moveit.scene.add_box("table", msg, size=(0.8, 0.8, 0.01))
|
self.moveit.scene.add_box("table", msg, size=(0.8, 0.8, 0.01))
|
||||||
|
|
||||||
|
|
||||||
|
@ -140,7 +140,7 @@ class GraspController:
|
|||||||
self.create_collision_scene()
|
self.create_collision_scene()
|
||||||
T_base_grasp = self.postprocess(grasp.pose)
|
T_base_grasp = self.postprocess(grasp.pose)
|
||||||
self.gripper.move(0.08)
|
self.gripper.move(0.08)
|
||||||
T_base_approach = T_base_grasp * Transform.t([0, 0, -0.06]) * self.T_grasp_ee
|
T_base_approach = T_base_grasp * Transform.t_[0, 0, -0.06] * self.T_grasp_ee
|
||||||
success, plan = self.moveit.plan(T_base_approach, 0.2, 0.2)
|
success, plan = self.moveit.plan(T_base_approach, 0.2, 0.2)
|
||||||
if success:
|
if success:
|
||||||
self.moveit.scene.clear()
|
self.moveit.scene.clear()
|
||||||
@ -149,7 +149,7 @@ class GraspController:
|
|||||||
self.moveit.gotoL(T_base_grasp * self.T_grasp_ee)
|
self.moveit.gotoL(T_base_grasp * self.T_grasp_ee)
|
||||||
rospy.sleep(0.5)
|
rospy.sleep(0.5)
|
||||||
self.gripper.grasp()
|
self.gripper.grasp()
|
||||||
T_base_retreat = Transform.t([0, 0, 0.05]) * T_base_grasp * self.T_grasp_ee
|
T_base_retreat = Transform.t_[0, 0, 0.05] * T_base_grasp * self.T_grasp_ee
|
||||||
self.moveit.gotoL(T_base_retreat)
|
self.moveit.gotoL(T_base_retreat)
|
||||||
rospy.sleep(1.0) # Wait to see whether the object slides out of the hand
|
rospy.sleep(1.0) # Wait to see whether the object slides out of the hand
|
||||||
success = self.gripper.read() > 0.002
|
success = self.gripper.read() > 0.002
|
||||||
@ -194,7 +194,7 @@ class GraspController:
|
|||||||
rot = T_base_grasp.rotation
|
rot = T_base_grasp.rotation
|
||||||
if rot.as_matrix()[:, 0][0] < 0: # Ensure that the camera is pointing forward
|
if rot.as_matrix()[:, 0][0] < 0: # Ensure that the camera is pointing forward
|
||||||
T_base_grasp.rotation = rot * Rotation.from_euler("z", np.pi)
|
T_base_grasp.rotation = rot * Rotation.from_euler("z", np.pi)
|
||||||
T_base_grasp *= Transform.t([0.0, 0.0, 0.01])
|
T_base_grasp *= Transform.t_[0.0, 0.0, 0.01]
|
||||||
return T_base_grasp
|
return T_base_grasp
|
||||||
|
|
||||||
def collect_info(self, result):
|
def collect_info(self, result):
|
||||||
|
@ -69,7 +69,7 @@ class Policy:
|
|||||||
|
|
||||||
def calibrate_task_frame(self):
|
def calibrate_task_frame(self):
|
||||||
xyz = np.r_[self.bbox.center[:2] - 0.15, self.bbox.min[2] - 0.05]
|
xyz = np.r_[self.bbox.center[:2] - 0.15, self.bbox.min[2] - 0.05]
|
||||||
self.T_base_task = Transform.t(xyz)
|
self.T_base_task = Transform.from_translation(xyz)
|
||||||
self.T_task_base = self.T_base_task.inv()
|
self.T_task_base = self.T_base_task.inv()
|
||||||
tf.broadcast(self.T_base_task, self.base_frame, self.task_frame)
|
tf.broadcast(self.T_base_task, self.base_frame, self.task_frame)
|
||||||
rospy.sleep(1.0) # Wait for tf tree to be updated
|
rospy.sleep(1.0) # Wait for tf tree to be updated
|
||||||
|
@ -90,9 +90,13 @@ class Visualizer(vgn.rviz.Visualizer):
|
|||||||
|
|
||||||
self.draw(markers)
|
self.draw(markers)
|
||||||
|
|
||||||
def point(self, frame, point):
|
def point(self, frame, position):
|
||||||
marker = create_sphere_marker(
|
marker = create_sphere_marker(
|
||||||
frame, Transform.t(point), np.full(3, 0.01), [0, 0, 1], "point"
|
frame,
|
||||||
|
Transform.from_translation(position),
|
||||||
|
np.full(3, 0.01),
|
||||||
|
[0, 0, 1],
|
||||||
|
"point",
|
||||||
)
|
)
|
||||||
self.draw([marker])
|
self.draw([marker])
|
||||||
|
|
||||||
|
@ -90,9 +90,9 @@ class Simulation:
|
|||||||
return AABBox(aabb_min, aabb_max)
|
return AABBox(aabb_min, aabb_max)
|
||||||
|
|
||||||
def check_for_grasps(self, bbox):
|
def check_for_grasps(self, bbox):
|
||||||
origin = Transform.t(self.scene.origin)
|
origin = Transform.from_translation(self.scene.origin)
|
||||||
origin.translation[2] -= 0.05
|
origin.translation[2] -= 0.05
|
||||||
center = Transform.t(self.scene.center)
|
center = Transform.from_translation(self.scene.center)
|
||||||
|
|
||||||
# First, reconstruct the scene from many views
|
# First, reconstruct the scene from many views
|
||||||
tsdf = UniformTSDFVolume(self.scene.length, 40)
|
tsdf = UniformTSDFVolume(self.scene.length, 40)
|
||||||
|
Loading…
x
Reference in New Issue
Block a user