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 import numpy as np
00034 import copy
00035
00036 import roslib; roslib.load_manifest('hrl_geom')
00037 import rospy
00038 from std_msgs.msg import Header
00039 from geometry_msgs.msg import PoseStamped, Pose, Point, Quaternion, PointStamped
00040 from geometry_msgs.msg import Transform, TransformStamped, Vector3
00041 from geometry_msgs.msg import Twist, TwistStamped
00042 import hrl_geom.transformations as trans
00043
00044
00045
00046
00047 class PoseConv(object):
00048 POSE_TYPES = [
00049 'pose_msg',
00050 'pose_stamped_msg',
00051 'point_msg',
00052 'point_stamped_msg',
00053 'tf_msg',
00054 'tf_stamped_msg',
00055 'twist_msg',
00056 'twist_stamped_msg',
00057 'homo_mat',
00058 'pos_rot',
00059 'pos_quat',
00060 'pos_euler']
00061
00062
00063
00064
00065 @staticmethod
00066 def get_type(*args):
00067 try:
00068 if type(args[0]) == str:
00069 return PoseConv.get_type(*args[1:])
00070 if len(args) == 1:
00071 if type(args[0]) is Pose:
00072 return 'pose_msg'
00073 elif type(args[0]) is PoseStamped:
00074 return 'pose_stamped_msg'
00075 elif type(args[0]) is Transform:
00076 return 'tf_msg'
00077 elif type(args[0]) is TransformStamped:
00078 return 'tf_stamped_msg'
00079 elif type(args[0]) is Twist:
00080 return 'twist_msg'
00081 elif type(args[0]) is TwistStamped:
00082 return 'twist_stamped_msg'
00083 elif type(args[0]) is Point:
00084 return 'point_msg'
00085 elif type(args[0]) is PointStamped:
00086 return 'point_stamped_msg'
00087 elif isinstance(args[0], (np.matrix, np.ndarray)) and np.shape(args[0]) == (4, 4):
00088 return 'homo_mat'
00089 elif isinstance(args[0], (tuple, list)) and len(args[0]) == 2:
00090 pos_arg = np.mat(args[0][0])
00091 rot_arg = np.mat(args[0][1])
00092 if pos_arg.shape != (1, 3) and pos_arg.shape != (3, 1):
00093 return None
00094 if rot_arg.shape == (3, 3):
00095 return 'pos_rot'
00096 else:
00097 if 1 not in rot_arg.shape:
00098 return None
00099 rot_arg = rot_arg.tolist()[0]
00100 if len(rot_arg) == 3:
00101 return 'pos_euler'
00102 elif len(rot_arg) == 4:
00103 return 'pos_quat'
00104 else:
00105 return None
00106 elif len(args) == 2:
00107 return PoseConv.get_type(((args[0], args[1]),))
00108 except:
00109 pass
00110 return None
00111
00112
00113
00114 @staticmethod
00115 def to_pose_msg(*args):
00116 header, homo_mat, quat_rot, _ = PoseConv._make_generic(args)
00117 if homo_mat is None:
00118 rospy.logwarn("[pose_converter] Unknown pose type.")
00119 return None
00120 else:
00121 return Pose(Point(*homo_mat[:3,3].T.A[0]), Quaternion(*quat_rot))
00122
00123
00124
00125 @staticmethod
00126 def to_pose_stamped_msg(*args):
00127 header, homo_mat, quat_rot, _ = PoseConv._make_generic(args)
00128 if homo_mat is None:
00129 rospy.logwarn("[pose_converter] Unknown pose type.")
00130 return None
00131 ps = PoseStamped()
00132 if header is None:
00133 ps.header.stamp = rospy.Time.now()
00134 else:
00135 ps.header.seq = header[0]
00136 ps.header.stamp = header[1]
00137 ps.header.frame_id = header[2]
00138 ps.pose = Pose(Point(*homo_mat[:3,3].T.A[0]), Quaternion(*quat_rot))
00139 return ps
00140
00141
00142
00143 @staticmethod
00144 def to_point_msg(*args):
00145 header, homo_mat, quat_rot, _ = PoseConv._make_generic(args)
00146 if homo_mat is None:
00147 rospy.logwarn("[pose_converter] Unknown pose type.")
00148 return None
00149 return Point(*homo_mat[:3,3].T.A[0])
00150
00151
00152
00153 @staticmethod
00154 def to_point_stamped_msg(*args):
00155 header, homo_mat, quat_rot, _ = PoseConv._make_generic(args)
00156 if homo_mat is None:
00157 rospy.logwarn("[pose_converter] Unknown pose type.")
00158 return None
00159 ps = PointStamped()
00160 if header is None:
00161 ps.header.stamp = rospy.Time.now()
00162 else:
00163 ps.header.seq = header[0]
00164 ps.header.stamp = header[1]
00165 ps.header.frame_id = header[2]
00166 ps.point = Point(*homo_mat[:3,3].T.A[0])
00167 return ps
00168
00169
00170
00171 @staticmethod
00172 def to_tf_msg(*args):
00173 header, homo_mat, quat_rot, _ = PoseConv._make_generic(args)
00174 if homo_mat is None:
00175 rospy.logwarn("[pose_converter] Unknown pose type.")
00176 return None
00177 else:
00178 return Transform(Vector3(*homo_mat[:3,3].T.A[0]), Quaternion(*quat_rot))
00179
00180
00181
00182 @staticmethod
00183 def to_tf_stamped_msg(*args):
00184 header, homo_mat, quat_rot, _ = PoseConv._make_generic(args)
00185 if homo_mat is None:
00186 rospy.logwarn("[pose_converter] Unknown pose type.")
00187 return None
00188 tf_stamped = TransformStamped()
00189 if header is None:
00190 tf_stamped.header.stamp = rospy.Time.now()
00191 else:
00192 tf_stamped.header.seq = header[0]
00193 tf_stamped.header.stamp = header[1]
00194 tf_stamped.header.frame_id = header[2]
00195 tf_stamped.transform = Transform(Vector3(*homo_mat[:3,3].T.A[0]), Quaternion(*quat_rot))
00196 return tf_stamped
00197
00198
00199
00200 @staticmethod
00201 def to_twist_msg(*args):
00202 _, homo_mat, _, euler_rot = PoseConv._make_generic(args)
00203 if homo_mat is None:
00204 rospy.logwarn("[pose_converter] Unknown pose type.")
00205 return None
00206 else:
00207 return Twist(Vector3(*homo_mat[:3,3].T.A[0]), Vector3(*euler_rot))
00208
00209
00210
00211 @staticmethod
00212 def to_twist_stamped_msg(*args):
00213 header, homo_mat, _, euler_rot = PoseConv._make_generic(args)
00214 if homo_mat is None:
00215 rospy.logwarn("[pose_converter] Unknown pose type.")
00216 return None
00217 twist_stamped = TwistStamped()
00218 header_msg = Header()
00219 if header is None:
00220 header_msg.stamp = rospy.Time.now()
00221 else:
00222 header_msg.seq = header[0]
00223 header_msg.stamp = header[1]
00224 header_msg.frame_id = header[2]
00225 return TwistStamped(header_msg, Twist(Vector3(*homo_mat[:3,3].T.A[0]), Vector3(*euler_rot)))
00226
00227
00228
00229 @staticmethod
00230 def to_homo_mat(*args):
00231 header, homo_mat, quat_rot, _ = PoseConv._make_generic(args)
00232 if homo_mat is None:
00233 rospy.logwarn("[pose_converter] Unknown pose type.")
00234 return None
00235 else:
00236 return homo_mat.copy()
00237
00238
00239
00240 @staticmethod
00241 def to_pos_rot(*args):
00242 header, homo_mat, quat_rot, _ = PoseConv._make_generic(args)
00243 if homo_mat is None:
00244 rospy.logwarn("[pose_converter] Unknown pose type.")
00245 return None, None
00246 else:
00247 return homo_mat[:3,3].copy(), homo_mat[:3,:3].copy()
00248
00249
00250
00251 @staticmethod
00252 def to_pos_quat(*args):
00253 header, homo_mat, quat_rot, _ = PoseConv._make_generic(args)
00254 if homo_mat is None:
00255 rospy.logwarn("[pose_converter] Unknown pose type.")
00256 return None, None
00257 else:
00258 return copy.copy(list(homo_mat[:3,3].T.A[0])), copy.copy(quat_rot)
00259
00260
00261
00262 @staticmethod
00263 def to_pos_euler(*args):
00264 header, homo_mat, quat_rot, euler_rot = PoseConv._make_generic(args)
00265 if homo_mat is None:
00266 rospy.logwarn("[pose_converter] Unknown pose type.")
00267 return None, None
00268 else:
00269 return copy.copy(list(homo_mat[:3,3].T.A[0])), copy.copy(euler_rot)
00270
00271 @staticmethod
00272 def _make_generic(args):
00273 try:
00274 if type(args[0]) == str:
00275 frame_id = args[0]
00276 header, homo_mat, rot_quat, rot_euler = PoseConv._make_generic(args[1:])
00277 if homo_mat is None:
00278 return None, None, None, None
00279 if header is None:
00280 header = [0, rospy.Time.now(), '']
00281 header[2] = frame_id
00282 return header, homo_mat, rot_quat, rot_euler
00283
00284 if len(args) == 2:
00285 return PoseConv._make_generic(((args[0], args[1]),))
00286 elif len(args) == 1:
00287 pose_type = PoseConv.get_type(*args)
00288 if pose_type is None:
00289 return None, None, None, None
00290 if pose_type == 'pose_msg':
00291 homo_mat, rot_quat, rot_euler = PoseConv._extract_pose_msg(args[0])
00292 return None, homo_mat, rot_quat, rot_euler
00293 elif pose_type == 'pose_stamped_msg':
00294 homo_mat, rot_quat, rot_euler = PoseConv._extract_pose_msg(args[0].pose)
00295 seq = args[0].header.seq
00296 stamp = args[0].header.stamp
00297 frame_id = args[0].header.frame_id
00298 return [seq, stamp, frame_id], homo_mat, rot_quat, rot_euler
00299 elif pose_type == 'tf_msg':
00300 homo_mat, rot_quat, rot_euler = PoseConv._extract_tf_msg(args[0])
00301 return None, homo_mat, rot_quat, rot_euler
00302 elif pose_type == 'tf_stamped_msg':
00303 homo_mat, rot_quat, rot_euler = PoseConv._extract_tf_msg(args[0].transform)
00304 seq = args[0].header.seq
00305 stamp = args[0].header.stamp
00306 frame_id = args[0].header.frame_id
00307 return [seq, stamp, frame_id], homo_mat, rot_quat, rot_euler
00308 elif pose_type == 'point_msg':
00309 homo_mat, rot_quat, rot_euler = PoseConv._extract_point_msg(args[0])
00310 return None, homo_mat, rot_quat, rot_euler
00311 elif pose_type == 'point_stamped_msg':
00312 homo_mat, rot_quat, rot_euler = PoseConv._extract_point_msg(args[0].point)
00313 seq = args[0].header.seq
00314 stamp = args[0].header.stamp
00315 frame_id = args[0].header.frame_id
00316 return [seq, stamp, frame_id], homo_mat, rot_quat, rot_euler
00317 elif pose_type == 'twist_msg':
00318 homo_mat, rot_quat, rot_euler = PoseConv._extract_twist_msg(args[0])
00319 return None, homo_mat, rot_quat, rot_euler
00320 elif pose_type == 'twist_stamped_msg':
00321 homo_mat, rot_quat, rot_euler = PoseConv._extract_twist_msg(args[0].twist)
00322 seq = args[0].header.seq
00323 stamp = args[0].header.stamp
00324 frame_id = args[0].header.frame_id
00325 return [seq, stamp, frame_id], homo_mat, rot_quat, rot_euler
00326 elif pose_type == 'homo_mat':
00327 return (None, np.mat(args[0]), trans.quaternion_from_matrix(args[0]).tolist(),
00328 trans.euler_from_matrix(args[0]))
00329 elif pose_type in ['pos_rot', 'pos_euler', 'pos_quat']:
00330 pos_arg = np.mat(args[0][0])
00331 rot_arg = np.mat(args[0][1])
00332 if pos_arg.shape == (1, 3):
00333
00334 pos = pos_arg.T
00335 elif pos_arg.shape == (3, 1):
00336 pos = pos_arg
00337
00338 if pose_type == 'pos_rot':
00339
00340 homo_mat = np.mat(np.eye(4))
00341 homo_mat[:3,:3] = rot_arg
00342 quat = trans.quaternion_from_matrix(homo_mat)
00343 rot_euler = trans.euler_from_matrix(homo_mat)
00344 else:
00345 if rot_arg.shape[1] == 1:
00346 rot_arg = rot_arg.T
00347 rot_list = rot_arg.tolist()[0]
00348 if pose_type == 'pos_euler':
00349
00350 homo_mat = np.mat(trans.euler_matrix(*rot_list))
00351 quat = trans.quaternion_from_euler(*rot_list)
00352 rot_euler = rot_list
00353 elif pose_type == 'pos_quat':
00354
00355 homo_mat = np.mat(trans.quaternion_matrix(rot_list))
00356 quat = rot_list
00357 rot_euler = trans.euler_from_quaternion(quat)
00358
00359 homo_mat[:3, 3] = pos
00360 return None, homo_mat, np.array(quat), rot_euler
00361 except:
00362 pass
00363
00364 return None, None, None, None
00365
00366 @staticmethod
00367 def _extract_pose_msg(pose):
00368 px = pose.position.x; py = pose.position.y; pz = pose.position.z
00369 ox = pose.orientation.x; oy = pose.orientation.y
00370 oz = pose.orientation.z; ow = pose.orientation.w
00371 quat = [ox, oy, oz, ow]
00372 rot_euler = trans.euler_from_quaternion(quat)
00373 homo_mat = np.mat(trans.quaternion_matrix(quat))
00374 homo_mat[:3,3] = np.mat([[px, py, pz]]).T
00375 return homo_mat, quat, rot_euler
00376
00377 @staticmethod
00378 def _extract_tf_msg(tf_msg):
00379 px = tf_msg.translation.x; py = tf_msg.translation.y; pz = tf_msg.translation.z
00380 ox = tf_msg.rotation.x; oy = tf_msg.rotation.y
00381 oz = tf_msg.rotation.z; ow = tf_msg.rotation.w
00382 quat = [ox, oy, oz, ow]
00383 rot_euler = trans.euler_from_quaternion(quat)
00384 homo_mat = np.mat(trans.quaternion_matrix(quat))
00385 homo_mat[:3,3] = np.mat([[px, py, pz]]).T
00386 return homo_mat, quat, rot_euler
00387
00388 @staticmethod
00389 def _extract_twist_msg(twist_msg):
00390 pos = [twist_msg.linear.x, twist_msg.linear.y, twist_msg.linear.z]
00391 rot_euler = [twist_msg.angular.x, twist_msg.angular.y, twist_msg.angular.z]
00392 quat = trans.quaternion_from_euler(*rot_euler, axes='sxyz')
00393 homo_mat = np.mat(trans.euler_matrix(*rot_euler))
00394 homo_mat[:3,3] = np.mat([pos]).T
00395 return homo_mat, quat, rot_euler
00396
00397 @staticmethod
00398 def _extract_point_msg(point_msg):
00399 pos = [point_msg.x, point_msg.y, point_msg.z]
00400 homo_mat = np.mat(np.eye(4))
00401 homo_mat[:3,3] = np.mat([pos]).T
00402 return homo_mat, [0., 0., 0., 1.], [0., 0., 0.]
00403
00404
00405 def main():
00406 rospy.init_node("pose_converter")
00407 pose = ([0.1, -0.5, 1.0], [0.04842544, 0.01236504, 0.24709477, 0.96770153])
00408 errors = 0
00409 for type_from in PoseConv.POSE_TYPES:
00410 for type_to in PoseConv.POSE_TYPES:
00411 print
00412 print "Types: FROM %s, TO %s" % (type_from, type_to)
00413 exec("from_pose = PoseConv.to_%s(pose)" % type_from)
00414 if from_pose is None or (type(from_pose) is tuple and from_pose[0] is None):
00415 print "from_pose ERROR\n" * 5
00416 errors += 1
00417 continue
00418 exec("to_pose = PoseConv.to_%s('base_link', from_pose)" % type_to)
00419 if to_pose is None or (type(to_pose) is tuple and to_pose[0] is None):
00420 print "to_pose ERROR\n" * 5
00421 errors += 1
00422 continue
00423 exec("back_pose = PoseConv.to_%s(to_pose)" % type_from)
00424 if back_pose is None or (type(back_pose) is tuple and back_pose[0] is None):
00425 print "back_pose ERROR\n" * 5
00426 errors += 1
00427 continue
00428 exec("orig_pose = PoseConv.to_pos_quat(back_pose)")
00429 if orig_pose is None or (type(orig_pose) is tuple and orig_pose[0] is None):
00430 print "orig_pose ERROR\n" * 5
00431 print pose
00432 print orig_pose
00433 errors += 1
00434 continue
00435 if not np.allclose(orig_pose[0], pose[0]):
00436 print "orig_pose pos ERROR\n" * 5
00437 print pose
00438 print orig_pose
00439 errors += 1
00440 continue
00441 if 'point' not in type_to + type_from and not np.allclose(orig_pose[1], pose[1]):
00442 print "orig_pose rot ERROR\n" * 5
00443 print pose
00444 print orig_pose
00445 errors += 1
00446 continue
00447 print "-" * 50
00448 if type_from != PoseConv.get_type(from_pose) or type_to != PoseConv.get_type(to_pose):
00449 print "get_type ERROR\n" * 5
00450 errors += 1
00451 continue
00452 print from_pose
00453 print "-" * 20
00454 print to_pose
00455 print "\n\nErrors: %d" % errors
00456
00457 if __name__ == "__main__":
00458 main()