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 from __future__ import division
00040 import roslib
00041 roslib.load_manifest('object_manipulator')
00042 import rospy
00043 import scipy
00044 import pdb
00045 import random
00046 import math
00047 import tf
00048 import scipy.linalg
00049 from geometry_msgs.msg import PoseStamped, Point, Pose, Vector3
00050 from object_manipulation_msgs.srv import FindClusterBoundingBox, FindClusterBoundingBoxResponse
00051 from convert_functions import *
00052
00053
00054
00055 class ClusterBoundingBoxFinder:
00056
00057 def __init__(self, tf_listener = None, tf_broadcaster = None):
00058
00059
00060 if tf_listener == None:
00061 self.tf_listener = tf.TransformListener()
00062 else:
00063 self.tf_listener = tf_listener
00064
00065
00066 if tf_broadcaster == None:
00067 self.tf_broadcaster = tf.TransformBroadcaster()
00068 else:
00069 self.tf_broadcaster = tf_broadcaster
00070
00071
00072
00073
00074 def pca(self, points):
00075 cov_mat = points[0:3,:] * points[0:3,:].T/scipy.shape(points)[1]
00076 (values, vectors) = scipy.linalg.eig(cov_mat)
00077 if values[1] > values[0]:
00078 directions = [vectors[:,1], vectors[:,0]]
00079 else:
00080 directions = [vectors[:,0], vectors[:,1]]
00081
00082 return directions
00083
00084
00085
00086 def mean_shift_xy(self, points):
00087 mean = [0]*2
00088 shifted_points = points.copy()
00089 for i in range(2):
00090 mean[i] = scipy.mean(points[i,:])
00091 shifted_points[i,:] -= mean[i]
00092 return (shifted_points, mean)
00093
00094
00095
00096 def remove_outliers(self, points):
00097
00098 points_filtered = points[:]
00099 empty_space_width = .02
00100 check_percent = .02
00101 edge_width = .005
00102
00103
00104 for dim in range(3):
00105
00106
00107 num_points = scipy.shape(points_filtered)[1]
00108 points_sorted = points_filtered[:, points_filtered[dim, :].argsort().tolist()[0]]
00109
00110
00111 ind = int(math.floor(num_points*(1-check_percent)))
00112 if points_sorted[dim, -1] - points_sorted[dim, ind] > empty_space_width:
00113
00114
00115 searcharr = scipy.array(points_sorted[dim, :]).flatten()
00116 searchval = points_sorted[dim, ind] + edge_width
00117 thres_ind = scipy.searchsorted(searcharr, searchval)
00118 if thres_ind != 0 and thres_ind != len(searcharr):
00119 points_filtered = points_sorted[:, 0:thres_ind]
00120 rospy.loginfo("chopped points off of dim %d, highest val = %5.3f, searchval = %5.3f"%(dim, points_sorted[dim, -1], searchval))
00121 else:
00122 points_filtered = points_sorted
00123
00124
00125 if dim != 2:
00126 ind = int(math.floor(num_points*check_percent))
00127 if points_filtered[dim, ind] - points_filtered[dim, 0] > empty_space_width:
00128
00129
00130 searcharr = scipy.array(points_sorted[dim, :]).flatten()
00131 searchval = points_sorted[dim, ind] - edge_width
00132 thres_ind = scipy.searchsorted(searcharr, searchval)
00133 if thres_ind != 0 and thres_ind != len(searcharr):
00134 points_filtered = points_filtered[:, thres_ind:-1]
00135 rospy.loginfo("chopped points off of dim -%d, lowest val = %5.3f, searchval = %5.3f"%(dim, points_sorted[dim, 0], searchval))
00136 return points_filtered
00137
00138
00139
00140
00141
00142 def find_object_frame_and_bounding_box(self, point_cloud):
00143
00144
00145
00146
00147 self.base_frame = rospy.get_param("~z_up_frame", point_cloud.header.frame_id)
00148
00149
00150 cluster_frame = point_cloud.header.frame_id
00151
00152 (points, cluster_to_base_frame) = transform_point_cloud(self.tf_listener, point_cloud, self.base_frame)
00153 if points == None:
00154 return (None, None, None)
00155
00156
00157
00158 table_height = points[2,:].min()
00159
00160
00161 (shifted_points, xy_mean) = self.mean_shift_xy(points)
00162 directions = self.pca(shifted_points[0:2, :])
00163
00164
00165
00166
00167 y_axis = scipy.mat([directions[1][0], directions[1][1], 0.])
00168 z_axis = scipy.mat([0.,0.,1.])
00169 x_axis = scipy.cross(y_axis, z_axis)
00170 rotmat = scipy.matrix(scipy.identity(4))
00171 rotmat[0:3, 0] = x_axis.T
00172 rotmat[0:3, 1] = y_axis.T
00173 rotmat[0:3, 2] = z_axis.T
00174 rotmat[2, 3] = table_height
00175 object_points = rotmat**-1 * shifted_points
00176
00177
00178 object_points = self.remove_outliers(object_points)
00179
00180
00181 object_bounding_box = [[0]*3 for i in range(2)]
00182 object_bounding_box_dims = [0]*3
00183 for dim in range(3):
00184 object_bounding_box[0][dim] = object_points[dim,:].min()
00185 object_bounding_box[1][dim] = object_points[dim,:].max()
00186 object_bounding_box_dims[dim] = object_bounding_box[1][dim] - object_bounding_box[0][dim]
00187
00188
00189 x_offset = object_bounding_box[1][0] - object_bounding_box_dims[0]/2.
00190 y_offset = object_bounding_box[1][1] - object_bounding_box_dims[1]/2.
00191 for i in range(2):
00192 object_bounding_box[i][0] -= x_offset
00193 object_bounding_box[i][1] -= y_offset
00194 object_points[0, :] -= x_offset
00195 object_points[1, :] -= y_offset
00196 offset_mat = scipy.mat(scipy.identity(4))
00197 offset_mat[0,3] = x_offset
00198 offset_mat[1,3] = y_offset
00199 rotmat = rotmat * offset_mat
00200
00201
00202
00203
00204 unshift_mean = scipy.identity(4)
00205 unshift_mean[0,3] = xy_mean[0]
00206 unshift_mean[1,3] = xy_mean[1]
00207 object_to_base_frame = unshift_mean*rotmat
00208 object_to_cluster_frame = cluster_to_base_frame**-1 * object_to_base_frame
00209
00210
00211 (object_frame_pos, object_frame_quat) = mat_to_pos_and_quat(object_to_cluster_frame)
00212 self.tf_broadcaster.sendTransform(object_frame_pos, object_frame_quat, rospy.Time.now(), "object_frame", cluster_frame)
00213
00214 return (object_points, object_bounding_box_dims, object_bounding_box, object_to_base_frame, object_to_cluster_frame)
00215
00216
00217