$search
00001 #!/usr/bin/python 00002 # Software License Agreement (BSD License) 00003 # 00004 # Copyright (c) 2009, Willow Garage, Inc. 00005 # All rights reserved. 00006 # 00007 # Redistribution and use in source and binary forms, with or without 00008 # modification, are permitted provided that the following conditions 00009 # are met: 00010 # 00011 # * Redistributions of source code must retain the above copyright 00012 # notice, this list of conditions and the following disclaimer. 00013 # * Redistributions in binary form must reproduce the above 00014 # copyright notice, this list of conditions and the following 00015 # disclaimer in the documentation and/or other materials provided 00016 # with the distribution. 00017 # * Neither the name of the Willow Garage nor the names of its 00018 # contributors may be used to endorse or promote products derived 00019 # from this software without specific prior written permission. 00020 # 00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 # POSSIBILITY OF SUCH DAMAGE. 00033 # 00034 # author: Kaijen Hsiao 00035 00036 ## @package convert_functions 00037 #helper functions for creating, transforming, and converting among messages, 00038 #scipy matrices, and lists 00039 00040 from __future__ import division 00041 import roslib 00042 roslib.load_manifest('object_manipulator') 00043 import rospy 00044 from geometry_msgs.msg import Transform, 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 numpy as np 00049 import scipy 00050 from sensor_msgs.msg import PointCloud, PointCloud2 00051 from object_manipulator.point_cloud import * 00052 00053 ##convert a PointCloud or PointCloud2 to a 4xn scipy matrix (x y z 1) 00054 def point_cloud_to_mat(point_cloud): 00055 if type(point_cloud) == type(PointCloud()): 00056 points = [[p.x, p.y, p.z, 1] for p in point_cloud.points] 00057 elif type(point_cloud) == type(PointCloud2()): 00058 points = [[p[0], p[1], p[2], 1] for p in read_points(point_cloud, field_names = 'xyz', skip_nans=True)] 00059 else: 00060 print "type not recognized:", type(point_cloud) 00061 return None 00062 points = scipy.matrix(points).T 00063 return points 00064 00065 00066 ##convert a 4xn scipy matrix (x y z 1) to a PointCloud 00067 def mat_to_point_cloud(mat, frame_id): 00068 pc = PointCloud() 00069 pc.header.frame_id = frame_id 00070 for n in range(mat.shape[1]): 00071 column = mat[:,n] 00072 point = Point32() 00073 point.x, point.y, point.z = column[0,0], column[1,0], column[2,0] 00074 pc.points.append(point) 00075 return pc 00076 00077 00078 ##transform a PointCloud or PointCloud2 to be a 4xn scipy matrix (x y z 1) in a new frame 00079 def transform_point_cloud(tf_listener, point_cloud, frame): 00080 points = point_cloud_to_mat(point_cloud) 00081 transform = get_transform(tf_listener, point_cloud.header.frame_id, frame) 00082 if transform == None: 00083 return (None, None) 00084 points = transform * points 00085 return (points, transform) 00086 00087 00088 ##get the 4x4 transformation matrix from frame1 to frame2 from TF 00089 def get_transform(tf_listener, frame1, frame2): 00090 temp_header = Header() 00091 temp_header.frame_id = frame1 00092 temp_header.stamp = rospy.Time(0) 00093 try: 00094 tf_listener.waitForTransform(frame1, frame2, rospy.Time(0), rospy.Duration(5)) 00095 except: 00096 rospy.logerr("tf transform was not there between %s and %s"%(frame1, frame2)) 00097 return None 00098 frame1_to_frame2 = tf_listener.asMatrix(frame2, temp_header) 00099 return scipy.matrix(frame1_to_frame2) 00100 00101 00102 def pose_to_mat(pose): 00103 '''Convert a pose message to a 4x4 numpy matrix. 00104 00105 Args: 00106 pose (geometry_msgs.msg.Pose): Pose rospy message class. 00107 00108 Returns: 00109 mat (numpy.matrix): 4x4 numpy matrix 00110 ''' 00111 quat = [pose.orientation.x, pose.orientation.y, pose.orientation.z, pose.orientation.w] 00112 pos = np.matrix([pose.position.x, pose.position.y, pose.position.z]).T 00113 mat = np.matrix(tf.transformations.quaternion_matrix(quat)) 00114 mat[0:3, 3] = pos 00115 return mat 00116 00117 00118 def mat_to_pose(mat, transform = None): 00119 '''Convert a homogeneous matrix to a Pose message, optionally premultiply by a transform. 00120 00121 Args: 00122 mat (numpy.ndarray): 4x4 array (or matrix) representing a homogenous transform. 00123 transform (numpy.ndarray): Optional 4x4 array representing additional transform 00124 00125 Returns: 00126 pose (geometry_msgs.msg.Pose): Pose message representing transform. 00127 ''' 00128 if transform != None: 00129 mat = np.dot(transform, mat) 00130 pose = Pose() 00131 pose.position.x = mat[0,3] 00132 pose.position.y = mat[1,3] 00133 pose.position.z = mat[2,3] 00134 quat = tf.transformations.quaternion_from_matrix(mat) 00135 pose.orientation.x = quat[0] 00136 pose.orientation.y = quat[1] 00137 pose.orientation.z = quat[2] 00138 pose.orientation.w = quat[3] 00139 return pose 00140 00141 def transform_to_mat(transform): 00142 '''Convert a tf transform to a 4x4 scipy mat. 00143 00144 Args: 00145 transform (geometry_msgs.msg.Transform): Transform rospy message class. 00146 00147 Returns: 00148 mat (numpy.matrix): 4x4 numpy matrix 00149 ''' 00150 quat = [transform.rotation.x, transform.rotation.y, transform.rotation.z, transform.rotation.w] 00151 pos = scipy.matrix([transform.translation.x, transform.translation.y, transform.translation.z]).T 00152 mat = scipy.matrix(tf.transformations.quaternion_matrix(quat)) 00153 mat[0:3, 3] = pos 00154 return mat 00155 00156 def mat_to_transform(mat, transform = None): 00157 '''Convert a 4x5 scipy matrix to a transform message. 00158 00159 Args: 00160 mat (numpy.matrix): 4x4 numpy matrix 00161 transform (numpy.ndarray): Optional 4x4 array representing additional transform 00162 00163 Returns: 00164 transform (geometry_msgs.msg.Transform): Transform rospy message class. 00165 ''' 00166 if transform != None: 00167 mat = transform * mat 00168 trans = np.array(mat[:3,3] / mat[3,3]).flat 00169 quat = tf.transformations.quaternion_from_matrix(mat) 00170 pose = Transform(Vector3(*trans), Quaternion(*quat)) 00171 return pose 00172 00173 ##convert a 4x4 scipy matrix to position and quaternion lists 00174 def mat_to_pos_and_quat(mat): 00175 quat = tf.transformations.quaternion_from_matrix(mat).tolist() 00176 pos = mat[0:3,3].T.tolist()[0] 00177 return (pos, quat) 00178 00179 00180 ##stamp a message by giving it a header with a timestamp of now 00181 def stamp_msg(msg, frame_id): 00182 msg.header.frame_id = frame_id 00183 msg.header.stamp = rospy.Time.now() 00184 00185 00186 ##make a PoseStamped out of a Pose 00187 def stamp_pose(pose, frame_id): 00188 pose_stamped = PoseStamped() 00189 stamp_msg(pose_stamped, frame_id) 00190 pose_stamped.pose = pose 00191 return pose_stamped 00192 00193 00194 ##make a Vector3Stamped out of a Vector3 00195 def stamp_vector3(vector3, frame_id): 00196 vector3_stamped = Vector3Stamped() 00197 stamp_msg(vector3_stamped, frame_id) 00198 vector3_stamped.vector = vector3 00199 return vector3_stamped 00200 00201 00202 ##set x, y, and z fields with a list 00203 def set_xyz(msg, xyz): 00204 msg.x = xyz[0] 00205 msg.y = xyz[1] 00206 msg.z = xyz[2] 00207 00208 00209 ##set x, y, z, and w fields with a list 00210 def set_xyzw(msg, xyzw): 00211 set_xyz(msg, xyzw) 00212 msg.w = xyzw[3] 00213 00214 00215 ##get x, y, and z fields in the form of a list 00216 def get_xyz(msg): 00217 return [msg.x, msg.y, msg.z] 00218 00219 00220 ##get x, y, z, and w fields in the form of a list 00221 def get_xyzw(msg): 00222 return [msg.x, msg.y, msg.z, msg.w] 00223 00224 00225 ##transform a poseStamped by a 4x4 scipy matrix 00226 def transform_pose_stamped(pose_stamped, transform, pre_or_post = "post"): 00227 00228 #convert the Pose to a 4x3 scipy matrix 00229 pose_mat = pose_to_mat(pose_stamped.pose) 00230 00231 #post-multiply by the transform 00232 if pre_or_post == "post": 00233 transformed_mat = pose_mat * transform 00234 else: 00235 transformed_mat = transform * pose_mat 00236 00237 #print "pose_mat:\n", ppmat(pose_mat) 00238 #print "transform:\n", ppmat(transform) 00239 #print "transformed_mat:\n", ppmat(transformed_mat) 00240 00241 (pos, quat) = mat_to_pos_and_quat(transformed_mat) 00242 00243 #create a new poseStamped 00244 new_pose_stamped = PoseStamped() 00245 new_pose_stamped.header = pose_stamped.header 00246 new_pose_stamped.pose = Pose(Point(*pos), Quaternion(*quat)) 00247 00248 return new_pose_stamped 00249 00250 00251 ##convert a pointStamped to a pos list in a desired frame 00252 def point_stamped_to_list(tf_listener, point, frame): 00253 00254 #convert the pointStamped to the desired frame, if necessary 00255 if point.header.frame_id != frame: 00256 tf_listener.waitForTransform(frame, point.header.frame_id, \ 00257 rospy.Time(0), rospy.Duration(5)) 00258 try: 00259 trans_point = tf_listener.transformPoint(frame, point) 00260 except rospy.ServiceException, e: 00261 print "point:\n", point 00262 print "frame:", frame 00263 rospy.logerr("point_stamped_to_list: error in transforming point from " + point.header.frame_id + " to " + frame + "error msg: %s"%e) 00264 return None 00265 else: 00266 trans_point = point 00267 00268 #extract position as a list 00269 pos = [trans_point.point.x, trans_point.point.y, trans_point.point.z] 00270 00271 return pos 00272 00273 00274 ##convert a Vector3Stamped to a rot list in a desired frame 00275 def vector3_stamped_to_list(tf_listener, vector3, frame): 00276 00277 #convert the vector3Stamped to the desired frame, if necessary 00278 if vector3.header.frame_id != frame: 00279 tf_listener.waitForTransform(frame, vector3.header.frame_id, \ 00280 rospy.Time(0), rospy.Duration(5)) 00281 try: 00282 trans_vector3 = tf_listener.transformVector3(frame, vector3) 00283 except rospy.ServiceException, e: 00284 print "vector3:\n", vector3 00285 print "frame:", frame 00286 rospy.logerr("vector3_stamped_to_list: error in transforming point from " + vector3.header.frame_id + " to " + frame + "error msg: %s"%e) 00287 return None 00288 else: 00289 trans_vector3 = vector3 00290 00291 #extract vect as a list 00292 vect = [trans_vector3.vector.x, trans_vector3.vector.y, trans_vector3.vector.z] 00293 00294 return vect 00295 00296 00297 ##convert a QuaternionStamped to a quat list in a desired frame 00298 def quaternion_stamped_to_list(tf_listener, quaternion, frame): 00299 00300 #convert the QuaternionStamped to the desired frame, if necessary 00301 if quaternion.header.frame_id != frame: 00302 tf_listener.waitForTransform(frame, quaternion.header.frame_id, \ 00303 rospy.Time(0), rospy.Duration(5)) 00304 try: 00305 trans_quat = tf_listener.transformQuaternion(frame, quaternion) 00306 except rospy.ServiceException, e: 00307 print "quaternion:\n", quaternion 00308 print "frame:", frame 00309 rospy.logerr("quaternion_stamped_to_list: error in transforming point from " + quaternion.header.frame_id + " to " + frame + "error msg: %s"%e) 00310 return None 00311 else: 00312 trans_quat = quaternion 00313 00314 #extract quat as a list 00315 quat = [trans_quat.quaternion.x, trans_quat.quaternion.y, trans_quat.quaternion.z, trans_quat.quaternion.w] 00316 00317 return quat 00318 00319 00320 ##change the frame of a Vector3Stamped 00321 def change_vector3_stamped_frame(tf_listener, vector3_stamped, frame): 00322 00323 if vector3_stamped.header.frame_id != frame: 00324 vector3_stamped.header.stamp = rospy.Time(0) 00325 tf_listener.waitForTransform(frame, vector3_stamped.header.frame_id,\ 00326 vector3_stamped.header.stamp, rospy.Duration(5)) 00327 try: 00328 trans_vector3 = tf_listener.transformVector3(frame, vector3_stamped) 00329 except rospy.ServiceException, e: 00330 rospy.logerr("change_vector3_stamped: error in transforming vector3 from " + vector3_stamped.header.frame_id + " to " + frame + "error msg: %s"%e) 00331 return None 00332 else: 00333 trans_vector3 = vector3_stamped 00334 00335 return trans_vector3 00336 00337 00338 ##change the frame of a PoseStamped 00339 def change_pose_stamped_frame(tf_listener, pose, frame): 00340 00341 #convert the PoseStamped to the desired frame, if necessary 00342 if pose.header.frame_id != frame: 00343 pose.header.stamp = rospy.Time(0) 00344 tf_listener.waitForTransform(frame, pose.header.frame_id, pose.header.stamp, rospy.Duration(5)) 00345 try: 00346 trans_pose = tf_listener.transformPose(frame, pose) 00347 except rospy.ServiceException, e: 00348 print "pose:\n", pose 00349 print "frame:", frame 00350 rospy.logerr("change_pose_stamped_frame: error in transforming pose from " + pose.header.frame_id + " to " + frame + "error msg: %s"%e) 00351 return None 00352 else: 00353 trans_pose = pose 00354 00355 return trans_pose 00356 00357 00358 ##convert a PoseStamped to pos and rot (quaternion) lists in a desired frame 00359 def pose_stamped_to_lists(tf_listener, pose, frame): 00360 00361 #change the frame, if necessary 00362 trans_pose = change_pose_stamped_frame(tf_listener, pose, frame) 00363 00364 #extract position and orientation as quaternion 00365 pos = [trans_pose.pose.position.x, trans_pose.pose.position.y, trans_pose.pose.position.z] 00366 rot = [trans_pose.pose.orientation.x, trans_pose.pose.orientation.y, \ 00367 trans_pose.pose.orientation.z, trans_pose.pose.orientation.w] 00368 00369 return (pos, rot) 00370 00371 00372 ##convert pos and rot lists (relative to in_frame) to a PoseStamped 00373 #(relative to to_frame) 00374 def lists_to_pose_stamped(tf_listener, pos, rot, in_frame, to_frame): 00375 00376 #stick lists in a PoseStamped 00377 m = PoseStamped() 00378 m.header.frame_id = in_frame 00379 m.header.stamp = rospy.get_rostime() 00380 m.pose = Pose(Point(*pos), Quaternion(*rot)) 00381 00382 try: 00383 pose_stamped = tf_listener.transformPose(to_frame, m) 00384 except rospy.ServiceException, e: 00385 rospy.logerr("error in transforming pose from " + in_frame + " to " + to_frame + "err msg: %s"%e) 00386 return None 00387 return pose_stamped 00388 00389 00390 ##create a PoseStamped message 00391 def create_pose_stamped(pose, frame_id = 'base_link'): 00392 m = PoseStamped() 00393 m.header.frame_id = frame_id 00394 #print "frame_id:", frame_id 00395 #m.header.stamp = rospy.get_rostime() 00396 m.header.stamp = rospy.Time() 00397 m.pose = Pose(Point(*pose[0:3]), Quaternion(*pose[3:7])) 00398 #print "desired position:", pplist(pose[0:3]) 00399 #print "desired orientation:", pplist(pose[3:7]) 00400 return m 00401 00402 00403 ##create a PointStamped message 00404 def create_point_stamped(point, frame_id = 'base_link'): 00405 m = PointStamped() 00406 m.header.frame_id = frame_id 00407 m.header.stamp = rospy.Time() 00408 #m.header.stamp = rospy.get_rostime() 00409 m.point = Point(*point) 00410 return m 00411 00412 00413 ##create a Vector3Stamped message 00414 def create_vector3_stamped(vector, frame_id = 'base_link'): 00415 m = Vector3Stamped() 00416 m.header.frame_id = frame_id 00417 m.header.stamp = rospy.Time() 00418 #m.header.stamp = rospy.get_rostime() 00419 m.vector = Vector3(*vector) 00420 return m 00421 00422 00423 ##pretty-print list to string 00424 def pplist(list): 00425 return ' '.join(['%5.3f'%x for x in list]) 00426 00427 00428 ##pretty-print numpy matrix to string 00429 def ppmat(mat): 00430 str = '' 00431 for i in range(mat.shape[0]): 00432 for j in range(mat.shape[1]): 00433 str += '%2.3f\t'%mat[i,j] 00434 str += '\n' 00435 return str