10 from jsk_topic_tools 
import ConnectionBasedTransport
 
   11 from sensor_msgs.msg 
import PointCloud2
 
   12 from sklearn.decomposition 
import PCA
 
   18         rospy.logwarn(
"This node is experiential one.")
 
   20         super(DetectGraspablePosesPcabase, self).
__init__()
 
   23         self.
hand_size = rospy.get_param(
'~hand_size', 0.13) 
 
   26         self.
pub_target_poses = self.advertise(
"~output/can_grasp_poses", PoseArray, queue_size=1)
 
   29         rospy.Subscriber(
'~input', PointCloud2, self.
callback)
 
   36         points = np.array(list(pc2.read_points(point_cloud, skip_nans=
True)))
 
   41             points_surface = points[:, [0, 1]] 
 
   43             points_surface = points[:, [1, 2]] 
 
   45             rospy.logwarn(
"direction should be x or z")
 
   47         pca = PCA(n_components=2)
 
   48         pca.fit(points_surface)
 
   49         new_points = pca.transform(points_surface)
 
   50         new_points = new_points[np.argsort(new_points[:, 0])]
 
   52         min_x = new_points[0, 0]
 
   53         max_x = new_points[-1, 0]
 
   58             candidate = new_points[np.where(new_points[:, 0] < (min_x + interval_m))]
 
   59             new_points = new_points[np.where(new_points[:, 0] >= (min_x + interval_m))]
 
   60             if len(candidate) > 0:
 
   61                 mean_x = np.mean(candidate, axis=0)[0]
 
   62                 mean_y = np.mean(candidate, axis=0)[1]
 
   63                 range_y = np.max(candidate[:, 1]) - np.min(candidate[:, 1])
 
   64                 discrete_xy_list.append([mean_x, mean_y, range_y])
 
   67         discrete_xy_list = np.array(discrete_xy_list)
 
   68         discrete_xy_list = discrete_xy_list[np.where(discrete_xy_list[:, 2] < self.
hand_size)]
 
   69         discrete_xy_list = discrete_xy_list[np.argsort(np.absolute(discrete_xy_list[:, 0]))]
 
   70         grasp_xy_list = pca.inverse_transform(discrete_xy_list[:, [0, 1]])
 
   72         search_range_m = interval_m
 
   74         grasp_position_list = []
 
   76         for grasp_xy 
in grasp_xy_list:
 
   78                 points_depth = points[np.where((points[:, 0] > grasp_xy[0] - search_range_m) &
 
   79                                                (points[:, 0] < grasp_xy[0] + search_range_m) &
 
   80                                                (points[:, 1] > grasp_xy[1] - search_range_m) &
 
   81                                                (points[:, 1] < grasp_xy[1] + search_range_m))]
 
   82                 points_depth = points_depth[:, 2]
 
   84                 points_depth = points[np.where((points[:, 1] > grasp_xy[0] - search_range_m) &
 
   85                                                (points[:, 1] < grasp_xy[0] + search_range_m) &
 
   86                                                (points[:, 2] > grasp_xy[1] - search_range_m) &
 
   87                                                (points[:, 2] < grasp_xy[1] + search_range_m))]
 
   88                 points_depth = points_depth[:, 0]
 
   90                 rospy.logwarn(
"direction should be x or z")
 
   91             if len(points_depth) > 0:
 
   92                 grasp_position = np.append(grasp_xy, np.mean(points_depth))
 
   94                 rospy.logwarn(
"it happens that something wrong")
 
   95             grasp_position_list.append(list(grasp_position))
 
   98         pub_msg.header = point_cloud.header
 
  100         trans_matrix = tf.transformations.identity_matrix()
 
  102             trans_matrix[0, 0] = 0
 
  103             trans_matrix[1, 0] = 0
 
  104             trans_matrix[2, 0] = -1
 
  105             trans_matrix[0, 1] = -1 * pca.components_[0, 1]
 
  106             trans_matrix[1, 1] = pca.components_[0, 0]
 
  107             trans_matrix[0, 2] = pca.components_[0, 0]
 
  108             trans_matrix[1, 2] = pca.components_[0, 1]
 
  109             trans_matrix[2, 2] = 0
 
  113             if pca.components_[0, 0] > 0:
 
  114                 trans_matrix[1, 1] = pca.components_[0, 0]
 
  115                 trans_matrix[2, 1] = pca.components_[0, 1]
 
  116                 trans_matrix[1, 2] = -1 * pca.components_[0, 1]
 
  117                 trans_matrix[2, 2] = pca.components_[0, 0]
 
  119                 trans_matrix[1, 1] = -1 * pca.components_[0, 0]
 
  120                 trans_matrix[2, 1] = -1 * pca.components_[0, 1]
 
  121                 trans_matrix[1, 2] = pca.components_[0, 1]
 
  122                 trans_matrix[2, 2] = -1 * pca.components_[0, 0]
 
  124             rospy.logwarn(
"direction should be x or z")
 
  126         quaternion = tf.transformations.quaternion_from_matrix(trans_matrix)
 
  128         for grasp_position 
in grasp_position_list:
 
  131                 pose.position.x = grasp_position[0]
 
  132                 pose.position.y = grasp_position[1]
 
  133                 pose.position.z = grasp_position[2]
 
  135                 pose.position.x = grasp_position[2]
 
  136                 pose.position.y = grasp_position[0]
 
  137                 pose.position.z = grasp_position[1]
 
  139                 rospy.logwarn(
"direction should x or z")
 
  140             pose.orientation.x = quaternion[0]
 
  141             pose.orientation.y = quaternion[1]
 
  142             pose.orientation.z = quaternion[2]
 
  143             pose.orientation.w = quaternion[3]
 
  144             pub_msg.poses.append(pose)
 
  148 if __name__ == 
'__main__':
 
  149     rospy.init_node(
'detect_graspable_poses_pcabase')