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 from __future__ import division
00041 import roslib
00042 roslib.load_manifest('object_manipulator')
00043 import rospy
00044 from object_manipulation_msgs.srv import FindClusterBoundingBox, FindClusterBoundingBoxResponse
00045 import object_manipulator.cluster_bounding_box_finder as cluster_bounding_box_finder
00046 import scipy
00047 from object_manipulator.convert_functions import *
00048
00049
00050 class ClusterBoundingBoxFinderServer:
00051
00052 def __init__(self):
00053 self.cbbf = cluster_bounding_box_finder.ClusterBoundingBoxFinder()
00054
00055 s = rospy.Service('find_cluster_bounding_box', FindClusterBoundingBox, self.find_cluster_bounding_box_callback)
00056
00057
00058
00059 def find_cluster_bounding_box_callback(self, req):
00060 rospy.loginfo("finding the bounding box for a point cluster")
00061
00062
00063 (object_points, object_bounding_box_dims, object_bounding_box, object_to_base_frame, object_to_cluster_frame) = \
00064 self.cbbf.find_object_frame_and_bounding_box(req.cluster)
00065
00066
00067 if object_points == None:
00068 return FindClusterBoundingBoxResponse(PoseStamped(), Vector3(0,0,0), 1)
00069
00070
00071 transform_mat = scipy.matrix([[1,0,0,0],
00072 [0,1,0,0],
00073 [0,0,1,object_bounding_box_dims[2]/2.],
00074 [0,0,0,1]])
00075 center_mat = object_to_base_frame * transform_mat
00076
00077
00078 pose = mat_to_pose(center_mat)
00079 pose_stamped = stamp_pose(pose, self.cbbf.base_frame)
00080
00081
00082 transformed_pose_stamped = change_pose_stamped_frame(self.cbbf.tf_listener, pose_stamped, req.cluster.header.frame_id)
00083
00084
00085 return FindClusterBoundingBoxResponse(transformed_pose_stamped, Vector3(*object_bounding_box_dims), 0)
00086
00087
00088 if __name__ == '__main__':
00089 rospy.init_node('cluster_bounding_box_finder', anonymous=True)
00090
00091 cbbfs = ClusterBoundingBoxFinderServer()
00092
00093 rospy.loginfo("cluster bounding box finder is ready for queries")
00094 rospy.spin()