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