00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041 import roslib; roslib.load_manifest('tabletop_collision_map_processing')
00042 import random, time, math, scipy, pdb
00043 import rospy
00044 from geometric_shapes_msgs.msg import Shape
00045 from tabletop_object_detector.msg import Table
00046 from collision_environment_msgs.msg import MakeStaticCollisionMapAction, MakeStaticCollisionMapGoal
00047 from mapping_msgs.msg import CollisionObject, AttachedCollisionObject, CollisionObjectOperation
00048 from actionlib_msgs.msg import GoalStatus
00049 from std_srvs.srv import Empty, EmptyRequest
00050 from geometric_shapes_msgs.msg import Shape
00051 import actionlib
00052 import tf
00053 from geometry_msgs.msg import PoseStamped, Point, Quaternion, Pose
00054
00055
00056 class CollisionMapInterface():
00057
00058 def __init__(self):
00059
00060
00061 rospy.loginfo("waiting for collision_map_self_occ_node/reset service")
00062 rospy.wait_for_service("collision_map_self_occ_node/reset")
00063 self.collision_map_reset_client = rospy.ServiceProxy("collision_map_self_occ_node/reset", Empty)
00064
00065 self.make_static_collision_map_client = actionlib.SimpleActionClient('make_static_collision_map', MakeStaticCollisionMapAction)
00066 rospy.loginfo("waiting for make_static_collision_map action server")
00067 self.make_static_collision_map_client.wait_for_server()
00068
00069 rospy.loginfo("advertising on collision object topics")
00070 self.object_in_map_pub = rospy.Publisher("collision_object", CollisionObject)
00071 self.attached_object_pub = rospy.Publisher("attached_collision_object", AttachedCollisionObject)
00072
00073 self.object_in_map_current_id = 0
00074 rospy.loginfo("done initializing collision map interface")
00075
00076
00077
00078 def reset_collision_map(self):
00079
00080
00081 try:
00082 resp = self.collision_map_reset_client(EmptyRequest())
00083 except rospy.ServiceException, e:
00084 rospy.logerr("error when calling collision_map_self_occ_node/reset: %s"%e)
00085 return 0
00086
00087
00088 reset_object = CollisionObject()
00089 reset_object.operation.operation = CollisionObjectOperation.REMOVE
00090 reset_object.header.frame_id = "base_link"
00091 reset_object.header.stamp = rospy.Time.now()
00092 reset_object.id = "all"
00093 self.object_in_map_pub.publish(reset_object)
00094
00095
00096 reset_attached_objects = AttachedCollisionObject()
00097 reset_attached_objects.link_name = "all"
00098 reset_attached_objects.object.header.frame_id = "base_link"
00099 reset_attached_objects.object.header.stamp = rospy.Time.now()
00100 reset_attached_objects.object = reset_object
00101 self.attached_object_pub.publish(reset_attached_objects)
00102
00103 rospy.loginfo("collision map reset")
00104 self.object_in_map_current_id = 0.
00105 return 1
00106
00107
00108
00109 def take_static_map(self):
00110 static_map_goal = MakeStaticCollisionMapGoal()
00111 static_map_goal.cloud_source = "full_cloud_filtered"
00112 static_map_goal.number_of_clouds = 2;
00113 self.make_static_collision_map_client.send_goal(static_map_goal)
00114
00115 if not self.make_static_collision_map_client.wait_for_result(rospy.Duration(30)):
00116 rospy.loginfo("collision map was not formed in allowed time")
00117 return 0
00118
00119 if self.make_static_collision_map_client.get_state() == GoalStatus.SUCCEEDED:
00120 rospy.loginfo("static map successfully updated")
00121 return 1
00122 else:
00123 rospy.loginfo("some other non-success state was reached for static collision map. Proceed with caution.")
00124 return 0
00125
00126
00127
00128
00129 def attach_object_to_gripper(self, object_name, whicharm = 'r'):
00130
00131 obj = AttachedCollisionObject()
00132
00133 obj.link_name = whicharm+"_gripper_r_finger_tip_link"
00134 obj.object.operation.operation = CollisionObjectOperation.ATTACH_AND_REMOVE_AS_OBJECT
00135 obj.object.header.stamp = rospy.Time.now()
00136 obj.object.header.frame_id = "base_link"
00137 obj.object.id = object_name
00138 touch_links = ["_gripper_palm_link", "_gripper_r_finger_tip_link", "_gripper_l_finger_tip_link", "_gripper_l_finger_link", "_gripper_r_finger_link"]
00139 obj.touch_links = [whicharm+link for link in touch_links]
00140 self.attached_object_pub.publish(obj)
00141
00142
00143
00144
00145 def detach_all_objects_from_gripper(self, whicharm = 'r'):
00146
00147 rospy.loginfo("detaching all objects from gripper %s"%whicharm)
00148 obj = AttachedCollisionObject()
00149 obj.object.header.stamp = rospy.Time.now()
00150 obj.object.header.frame_id = "base_link"
00151 obj.link_name = whicharm+"_gripper_r_finger_tip_link"
00152 obj.object.operation.operation = CollisionObjectOperation.REMOVE
00153 self.attached_object_pub.publish(obj)
00154
00155
00156
00157
00158
00159 def detach_and_add_back_objects_attached_to_gripper(self, whicharm = 'r', object_collision_name = None):
00160
00161 rospy.loginfo("detaching all objects from gripper %s and adding them back to the collision map"%whicharm)
00162
00163 if object_collision_name == None:
00164 rospy.loginfo("need to specify the object name! Detaching and not adding back object.")
00165 self.detach_all_objects_from_gripper(whicharm)
00166 return
00167
00168 obj = AttachedCollisionObject()
00169 obj.object.header.stamp = rospy.Time.now()
00170 obj.object.header.frame_id = "base_link"
00171 obj.link_name = whicharm+"_gripper_r_finger_tip_link"
00172 obj.object.id = object_collision_name
00173 obj.object.operation.operation = CollisionObjectOperation.DETACH_AND_ADD_AS_OBJECT
00174 self.attached_object_pub.publish(obj)
00175
00176
00177
00178 def pose_to_mat(self, pose):
00179 quat = [pose.orientation.x, pose.orientation.y, pose.orientation.z, pose.orientation.w]
00180 pos = scipy.matrix([pose.position.x, pose.position.y, pose.position.z]).T
00181 mat = scipy.matrix(tf.transformations.quaternion_matrix(quat))
00182 mat[0:3, 3] = pos
00183 return mat
00184
00185
00186
00187 def mat_to_pose(self, mat):
00188 pose = Pose()
00189 pose.position.x = mat[0,3]
00190 pose.position.y = mat[1,3]
00191 pose.position.z = mat[2,3]
00192 quat = tf.transformations.quaternion_from_matrix(mat)
00193 pose.orientation.x = quat[0]
00194 pose.orientation.y = quat[1]
00195 pose.orientation.z = quat[2]
00196 pose.orientation.w = quat[3]
00197 return pose
00198
00199
00200
00201 def process_collision_geometry_for_table(self, firsttable, additional_tables = []):
00202
00203 table_object = CollisionObject()
00204 table_object.operation.operation = CollisionObjectOperation.ADD
00205 table_object.header.frame_id = firsttable.pose.header.frame_id
00206 table_object.header.stamp = rospy.Time.now()
00207
00208
00209 for table in [firsttable,]+additional_tables:
00210 object = Shape()
00211 object.type = Shape.BOX;
00212 object.dimensions.append(math.fabs(table.x_max-table.x_min))
00213 object.dimensions.append(math.fabs(table.y_max-table.y_min))
00214 object.dimensions.append(0.01)
00215 table_object.shapes.append(object)
00216
00217
00218 table_mat = self.pose_to_mat(firsttable.pose.pose)
00219 table_offset = scipy.matrix([(firsttable.x_min + firsttable.x_max)/2.0, (firsttable.y_min + firsttable.y_max)/2.0, 0.0]).T
00220 table_offset_mat = scipy.matrix(scipy.identity(4))
00221 table_offset_mat[0:3,3] = table_offset
00222 table_center = table_mat * table_offset_mat
00223 origin_pose = self.mat_to_pose(table_center)
00224 table_object.poses.append(origin_pose)
00225
00226 table_object.id = "table"
00227 self.object_in_map_pub.publish(table_object)
00228
00229
00230
00231 def get_next_object_name(self):
00232 string = "graspable_object_"+str(self.object_in_map_current_id)
00233 self.object_in_map_current_id += 1
00234 return string
00235
00236
00237
00238 def add_collision_box(self, box_pose, box_dims, frame_id, collision_name):
00239
00240 rospy.loginfo("adding box to collision map")
00241 box = CollisionObject()
00242 box.operation.operation = CollisionObjectOperation.ADD
00243 box.header.frame_id = frame_id
00244 box.header.stamp = rospy.Time.now()
00245 shape = Shape()
00246 shape.type = Shape.BOX
00247 shape.dimensions = box_dims
00248 box.shapes.append(shape)
00249 box.poses.append(box_pose)
00250 box.id = collision_name
00251 self.object_in_map_pub.publish(box)
00252
00253
00254
00255 def process_collision_geometry_for_cluster(self, cluster):
00256
00257 rospy.loginfo("adding cluster with %d points to collision map"%len(cluster.points))
00258
00259 many_boxes = CollisionObject()
00260
00261 many_boxes.operation.operation = CollisionObjectOperation.ADD
00262 many_boxes.header = cluster.header
00263 many_boxes.header.stamp = rospy.Time.now()
00264 num_to_use = int(len(cluster.points)/100.0)
00265 random_indices = range(len(cluster.points))
00266 scipy.random.shuffle(random_indices)
00267 random_indices = random_indices[0:num_to_use]
00268 for i in range(num_to_use):
00269 shape = Shape()
00270 shape.type = Shape.BOX
00271 shape.dimensions = [.005]*3
00272 pose = Pose()
00273 pose.position.x = cluster.points[random_indices[i]].x
00274 pose.position.y = cluster.points[random_indices[i]].y
00275 pose.position.z = cluster.points[random_indices[i]].z
00276 pose.orientation = Quaternion(*[0,0,0,1])
00277 many_boxes.shapes.append(shape)
00278 many_boxes.poses.append(pose)
00279
00280 collision_name = self.get_next_object_name()
00281 many_boxes.id = collision_name
00282 self.object_in_map_pub.publish(many_boxes)
00283 return collision_name
00284
00285
00286
00287 def remove_collision_object(self, collision_name):
00288
00289 reset_object = CollisionObject()
00290 reset_object.operation.operation = CollisionObjectOperation.REMOVE
00291 reset_object.header.frame_id = "base_link"
00292 reset_object.header.stamp = rospy.Time.now()
00293 reset_object.id = collision_name
00294 self.object_in_map_pub.publish(reset_object)