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 geometry_msgs.msg import Pose, PoseStamped, Point, Point32, PointStamped, Vector3, Vector3Stamped, Quaternion, QuaternionStamped
00045 from sensor_msgs.msg import PointCloud
00046 from std_msgs.msg import Header
00047 import tf.transformations
00048 import scipy
00049 from sensor_msgs.msg import PointCloud
00050
00051
00052 def point_cloud_to_mat(point_cloud):
00053 points = [[p.x, p.y, p.z, 1] for p in point_cloud.points]
00054 points = scipy.matrix(points).T
00055 return points
00056
00057
00058 def mat_to_point_cloud(mat, frame_id):
00059 pc = PointCloud()
00060 pc.header.frame_id = frame_id
00061 for n in range(mat.shape[1]):
00062 column = mat[:,n]
00063 point = Point32()
00064 point.x, point.y, point.z = column[0,0], column[1,0], column[2,0]
00065 pc.points.append(point)
00066 return pc
00067
00068
00069
00070 def transform_point_cloud(tf_listener, point_cloud, frame):
00071 points = point_cloud_to_mat(point_cloud)
00072 point_cloud.header.stamp = rospy.Time(0)
00073
00074
00075 try:
00076 tf_listener.waitForTransform(frame, point_cloud.header.frame_id, rospy.Time(0), rospy.Duration(5))
00077 except:
00078 rospy.logerr("tf transform was not there!!")
00079 return (None, None)
00080
00081
00082 transform = tf_listener.asMatrix(frame, point_cloud.header)
00083 transform = scipy.matrix(transform)
00084 points = transform * points
00085
00086
00087
00088
00089
00090 return (points, transform)
00091
00092
00093
00094 def get_transform(tf_listener, frame1, frame2):
00095 temp_header = Header()
00096 temp_header.frame_id = frame1
00097 temp_header.stamp = rospy.Time(0)
00098 try:
00099 frame1_to_frame2 = tf_listener.asMatrix(frame2, temp_header)
00100 except:
00101 rospy.logerr("tf transform was not there between %s and %s"%(frame1, frame2))
00102 return scipy.matrix(scipy.identity(4))
00103 return scipy.matrix(frame1_to_frame2)
00104
00105
00106
00107 def pose_to_mat(pose):
00108 quat = [pose.orientation.x, pose.orientation.y, pose.orientation.z, pose.orientation.w]
00109 pos = scipy.matrix([pose.position.x, pose.position.y, pose.position.z]).T
00110 mat = scipy.matrix(tf.transformations.quaternion_matrix(quat))
00111 mat[0:3, 3] = pos
00112 return mat
00113
00114
00115
00116
00117 def mat_to_pose(mat, transform = None):
00118 if transform != None:
00119 mat = transform * mat
00120 pose = Pose()
00121 pose.position.x = mat[0,3]
00122 pose.position.y = mat[1,3]
00123 pose.position.z = mat[2,3]
00124 quat = tf.transformations.quaternion_from_matrix(mat)
00125 pose.orientation.x = quat[0]
00126 pose.orientation.y = quat[1]
00127 pose.orientation.z = quat[2]
00128 pose.orientation.w = quat[3]
00129 return pose
00130
00131
00132
00133 def transform_to_mat(transform):
00134 quat = [transform.rotation.x, transform.rotation.y, transform.rotation.z, transform.rotation.w]
00135 pos = scipy.matrix([transform.translation.x, transform.translation.y, transform.translation.z]).T
00136 mat = scipy.matrix(tf.transformations.quaternion_matrix(quat))
00137 mat[0:3, 3] = pos
00138 return mat
00139
00140
00141
00142 def mat_to_pos_and_quat(mat):
00143 quat = tf.transformations.quaternion_from_matrix(mat).tolist()
00144 pos = mat[0:3,3].T.tolist()[0]
00145 return (pos, quat)
00146
00147
00148
00149 def stamp_msg(msg, frame_id):
00150 msg.header.frame_id = frame_id
00151 msg.header.stamp = rospy.Time.now()
00152
00153
00154
00155 def stamp_pose(pose, frame_id):
00156 pose_stamped = PoseStamped()
00157 stamp_msg(pose_stamped, frame_id)
00158 pose_stamped.pose = pose
00159 return pose_stamped
00160
00161
00162
00163 def stamp_vector3(vector3, frame_id):
00164 vector3_stamped = Vector3Stamped()
00165 stamp_msg(vector3_stamped, frame_id)
00166 vector3_stamped.vector = vector3
00167 return vector3_stamped
00168
00169
00170
00171 def set_xyz(msg, xyz):
00172 msg.x = xyz[0]
00173 msg.y = xyz[1]
00174 msg.z = xyz[2]
00175
00176
00177
00178 def set_xyzw(msg, xyzw):
00179 set_xyz(msg, xyzw)
00180 msg.w = xyzw[3]
00181
00182
00183
00184 def get_xyz(msg):
00185 return [msg.x, msg.y, msg.z]
00186
00187
00188
00189 def get_xyzw(msg):
00190 return [msg.x, msg.y, msg.z, msg.w]
00191
00192
00193
00194 def transform_pose_stamped(pose_stamped, transform, pre_or_post = "post"):
00195
00196
00197 pose_mat = pose_to_mat(pose_stamped.pose)
00198
00199
00200 if pre_or_post == "post":
00201 transformed_mat = pose_mat * transform
00202 else:
00203 transformed_mat = transform * pose_mat
00204
00205
00206
00207
00208
00209 (pos, quat) = mat_to_pos_and_quat(transformed_mat)
00210
00211
00212 new_pose_stamped = PoseStamped()
00213 new_pose_stamped.header = pose_stamped.header
00214 new_pose_stamped.pose = Pose(Point(*pos), Quaternion(*quat))
00215
00216 return new_pose_stamped
00217
00218
00219
00220 def point_stamped_to_list(tf_listener, point, frame):
00221
00222
00223 if point.header.frame_id != frame:
00224 tf_listener.waitForTransform(frame, point.header.frame_id, \
00225 rospy.Time(0), rospy.Duration(5))
00226 try:
00227 trans_point = tf_listener.transformPoint(frame, point)
00228 except rospy.ServiceException, e:
00229 print "point:\n", point
00230 print "frame:", frame
00231 rospy.logerr("point_stamped_to_list: error in transforming point from " + point.header.frame_id + " to " + frame + "error msg: %s"%e)
00232 return None
00233 else:
00234 trans_point = point
00235
00236
00237 pos = [trans_point.point.x, trans_point.point.y, trans_point.point.z]
00238
00239 return pos
00240
00241
00242
00243 def vector3_stamped_to_list(tf_listener, vector3, frame):
00244
00245
00246 if vector3.header.frame_id != frame:
00247 tf_listener.waitForTransform(frame, vector3.header.frame_id, \
00248 rospy.Time(0), rospy.Duration(5))
00249 try:
00250 trans_vector3 = tf_listener.transformVector3(frame, vector3)
00251 except rospy.ServiceException, e:
00252 print "vector3:\n", vector3
00253 print "frame:", frame
00254 rospy.logerr("vector3_stamped_to_list: error in transforming point from " + vector3.header.frame_id + " to " + frame + "error msg: %s"%e)
00255 return None
00256 else:
00257 trans_vector3 = vector3
00258
00259
00260 vect = [trans_vector3.vector.x, trans_vector3.vector.y, trans_vector3.vector.z]
00261
00262 return vect
00263
00264
00265
00266 def quaternion_stamped_to_list(tf_listener, quaternion, frame):
00267
00268
00269 if quaternion.header.frame_id != frame:
00270 tf_listener.waitForTransform(frame, quaternion.header.frame_id, \
00271 rospy.Time(0), rospy.Duration(5))
00272 try:
00273 trans_quat = tf_listener.transformQuaternion(frame, quaternion)
00274 except rospy.ServiceException, e:
00275 print "quaternion:\n", quaternion
00276 print "frame:", frame
00277 rospy.logerr("quaternion_stamped_to_list: error in transforming point from " + quaternion.header.frame_id + " to " + frame + "error msg: %s"%e)
00278 return None
00279 else:
00280 trans_quat = quaternion
00281
00282
00283 quat = [trans_quat.quaternion.x, trans_quat.quaternion.y, trans_quat.quaternion.z, trans_quat.quaternion.w]
00284
00285 return quat
00286
00287
00288
00289 def change_vector3_stamped_frame(tf_listener, vector3_stamped, frame):
00290
00291 if vector3_stamped.header.frame_id != frame:
00292 vector3_stamped.header.stamp = rospy.Time(0)
00293 tf_listener.waitForTransform(frame, vector3_stamped.header.frame_id,\
00294 vector3_stamped.header.stamp, rospy.Duration(5))
00295 try:
00296 trans_vector3 = tf_listener.transformVector3(frame, vector3_stamped)
00297 except rospy.ServiceException, e:
00298 rospy.logerr("change_vector3_stamped: error in transforming vector3 from " + vector3_stamped.header.frame_id + " to " + frame + "error msg: %s"%e)
00299 return None
00300 else:
00301 trans_vector3 = vector3_stamped
00302
00303 return trans_vector3
00304
00305
00306
00307 def change_pose_stamped_frame(tf_listener, pose, frame):
00308
00309
00310 if pose.header.frame_id != frame:
00311 pose.header.stamp = rospy.Time(0)
00312 tf_listener.waitForTransform(frame, pose.header.frame_id, pose.header.stamp, rospy.Duration(5))
00313 try:
00314 trans_pose = tf_listener.transformPose(frame, pose)
00315 except rospy.ServiceException, e:
00316 print "pose:\n", pose
00317 print "frame:", frame
00318 rospy.logerr("change_pose_stamped_frame: error in transforming pose from " + pose.header.frame_id + " to " + frame + "error msg: %s"%e)
00319 return None
00320 else:
00321 trans_pose = pose
00322
00323 return trans_pose
00324
00325
00326
00327 def pose_stamped_to_lists(tf_listener, pose, frame):
00328
00329
00330 trans_pose = change_pose_stamped_frame(tf_listener, pose, frame)
00331
00332
00333 pos = [trans_pose.pose.position.x, trans_pose.pose.position.y, trans_pose.pose.position.z]
00334 rot = [trans_pose.pose.orientation.x, trans_pose.pose.orientation.y, \
00335 trans_pose.pose.orientation.z, trans_pose.pose.orientation.w]
00336
00337 return (pos, rot)
00338
00339
00340
00341
00342 def lists_to_pose_stamped(tf_listener, pos, rot, in_frame, to_frame):
00343
00344
00345 m = PoseStamped()
00346 m.header.frame_id = in_frame
00347 m.header.stamp = rospy.get_rostime()
00348 m.pose = Pose(Point(*pos), Quaternion(*rot))
00349
00350 try:
00351 pose_stamped = tf_listener.transformPose(to_frame, m)
00352 except rospy.ServiceException, e:
00353 rospy.logerr("error in transforming pose from " + in_frame + " to " + to_frame + "err msg: %s"%e)
00354 return None
00355 return pose_stamped
00356
00357
00358
00359 def create_pose_stamped(pose, frame_id = 'base_link'):
00360 m = PoseStamped()
00361 m.header.frame_id = frame_id
00362
00363
00364 m.header.stamp = rospy.Time()
00365 m.pose = Pose(Point(*pose[0:3]), Quaternion(*pose[3:7]))
00366
00367
00368 return m
00369
00370
00371
00372 def create_point_stamped(point, frame_id = 'base_link'):
00373 m = PointStamped()
00374 m.header.frame_id = frame_id
00375 m.header.stamp = rospy.Time()
00376
00377 m.point = Point(*point)
00378 return m
00379
00380
00381
00382 def create_vector3_stamped(vector, frame_id = 'base_link'):
00383 m = Vector3Stamped()
00384 m.header.frame_id = frame_id
00385 m.header.stamp = rospy.Time()
00386
00387 m.vector = Vector3(*vector)
00388 return m
00389
00390
00391
00392 def pplist(list):
00393 return ' '.join(['%5.3f'%x for x in list])
00394
00395
00396
00397 def ppmat(mat):
00398 str = ''
00399 for i in range(mat.shape[0]):
00400 for j in range(mat.shape[1]):
00401 str += '%2.3f\t'%mat[i,j]
00402 str += '\n'
00403 return str