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 from __future__ import with_statement
00036
00037 import os
00038 import sys
00039
00040 import roslib.message
00041 import roslib.packages
00042
00043 import rospy
00044
00045 _error = None
00046 try:
00047 import geometry_msgs.msg
00048 except ImportError:
00049 _error = "cannot import geometry_msgs, tf integration will be disabled"
00050 try:
00051 import tf
00052 except ImportError:
00053 _error = "cannot import tf, tf integration will be disabled"
00054
00055
00056 from rosh.impl.exceptions import InvalidPlugin
00057 from rosh.impl.namespace import Namespace, Concept
00058
00059
00060 import rosh.impl.proc
00061
00062 from rosh_geometry.geometry import PoseStamped, Point, Quaternion
00063
00064 class TFFrame(Namespace):
00065
00066 def __init__(self, name, config):
00067 """
00068 ctor.
00069 @param config: Namespace configuration instance with additional 'listener' attribute.
00070 @type config: L{NamespaceConfig}
00071 """
00072 super(TFFrame, self).__init__(name, config)
00073
00074 def _list(self):
00075 """
00076 Override Namespace._list()
00077 """
00078 try:
00079 return self._config.listener.getFrameStrings()
00080 except:
00081 return []
00082
00083 def __repr__(self):
00084 return self.__str__()
00085
00086 def __str__(self):
00087 return self._name
00088
00089 def __call__(self, target):
00090 """
00091 @return: current transform
00092 @rtype: L{Transform}
00093 """
00094 translation, rotation = self._config.listener.lookupTransform(self._name, target, rospy.Time(0))
00095 return PoseStamped(Point(*translation), Quaternion(*rotation), target)
00096
00097 class Transform(object):
00098 def __init__(self, translation, rotation):
00099 self.translation = translation
00100 self.rotation = rotation
00101
00102 def __repr__(self):
00103 return self.__str__()
00104
00105 def __str__(self):
00106 return "- Translation: %s\n- Rotation: %s"%(self.translation, self.rotation)
00107
00108 class TFFrames(Concept):
00109
00110 def __init__(self, ctx, lock):
00111 if _error:
00112 raise InvalidPlugin(_error)
00113 super(TFFrames, self).__init__(ctx, lock, TFFrame)
00114
00115 self._config.listener = tf.TransformListener()
00116
00117 def __setattr__(self, key, value):
00118 if key.startswith('_'):
00119 return object.__setattr__(self, key, value)
00120 else:
00121 return self._root.__setitem__(key, value)
00122
00123 def _show(self):
00124 show_concept(self)
00125
00126 def __call__(self, obj, frame_id):
00127 l = self._config.listener
00128 if hasattr(obj, '_transform'):
00129 return obj._transform(l, frame_id)
00130 elif isinstance(obj, roslib.message.Message):
00131
00132
00133
00134
00135 if isinstance(obj, geometry_msgs.msg.PointStamped):
00136 return l.transformPoint(frame_id, obj)
00137 elif isinstance(obj, geometry_msgs.msg.PoseStamped):
00138 return l.transformPose(frame_id, obj)
00139 elif isinstance(obj, geometry_msgs.msg.QuaternionStamped):
00140 return l.transformQuaternion(frame_id, obj)
00141 elif isinstance(obj, geometry_msgs.msg.Vector3Stamped):
00142 return l.transformVector3(frame_id, obj)
00143 else:
00144 raise ValueError("message is not transformable")
00145 else:
00146 raise ValueError("object is not transformable")
00147
00148 def show_concept(tf_frames):
00149 dotcode = tf_frames._config.listener.allFramesAsDot()
00150 d = roslib.packages.get_pkg_dir('rosh')
00151 mod = os.path.join(d, 'src', 'rosh', 'impl', 'xdot.py')
00152
00153 rosh.impl.proc.run(tf_frames._config, ['python', mod, '--raw', dotcode])