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 _getAttributeNames(self):
00084
00085 ns = self._ns.lstrip('/')
00086
00087
00088 return set([s[len(ns):].split('/')[0].strip('/') for s in self._list() if s.startswith(ns)])
00089
00090 def __repr__(self):
00091 return self.__str__()
00092
00093 def __str__(self):
00094 return self._name
00095
00096 def __call__(self, target):
00097 """
00098 @return: current transform
00099 @rtype: L{Transform}
00100 """
00101 translation, rotation = self._config.listener.lookupTransform(self._name, target, rospy.Time(0))
00102 return PoseStamped(Point(*translation), Quaternion(*rotation), target)
00103
00104 class Transform(object):
00105 def __init__(self, translation, rotation):
00106 self.translation = translation
00107 self.rotation = rotation
00108
00109 def __repr__(self):
00110 return self.__str__()
00111
00112 def __str__(self):
00113 return "- Translation: %s\n- Rotation: %s"%(self.translation, self.rotation)
00114
00115 class TFFrames(Concept):
00116
00117 def __init__(self, ctx, lock):
00118 if _error:
00119 raise InvalidPlugin(_error)
00120 super(TFFrames, self).__init__(ctx, lock, TFFrame)
00121
00122 self._config.listener = tf.TransformListener()
00123
00124 def __setattr__(self, key, value):
00125 if key.startswith('_'):
00126 return object.__setattr__(self, key, value)
00127 else:
00128 return self._root.__setitem__(key, value)
00129
00130 def _show(self):
00131 show_concept(self)
00132
00133 def __call__(self, obj, frame_id):
00134 l = self._config.listener
00135 if hasattr(obj, '_transform'):
00136 return obj._transform(l, frame_id)
00137 elif isinstance(obj, roslib.message.Message):
00138
00139
00140
00141
00142 if isinstance(obj, geometry_msgs.msg.PointStamped):
00143 return l.transformPoint(frame_id, obj)
00144 elif isinstance(obj, geometry_msgs.msg.PoseStamped):
00145 return l.transformPose(frame_id, obj)
00146 elif isinstance(obj, geometry_msgs.msg.QuaternionStamped):
00147 return l.transformQuaternion(frame_id, obj)
00148 elif isinstance(obj, geometry_msgs.msg.Vector3Stamped):
00149 return l.transformVector3(frame_id, obj)
00150 else:
00151 raise ValueError("message is not transformable")
00152 else:
00153 raise ValueError("object is not transformable")
00154
00155 def show_concept(tf_frames):
00156 dotcode = tf_frames._config.listener.allFramesAsDot()
00157 d = roslib.packages.get_pkg_dir('rosh')
00158 mod = os.path.join(d, 'src', 'rosh', 'impl', 'xdot.py')
00159
00160 rosh.impl.proc.run(tf_frames._config, ['python', mod, '--raw', dotcode])