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


object_recognition_clusters
Author(s): Bence Magyar , Kaijen Hsiao
autogenerated on Wed Aug 26 2015 14:58:56