Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Make python scripts Python3 compatible. #151

Merged
merged 2 commits into from
Jul 24, 2017
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 5 additions & 3 deletions tf/scripts/bullet_migration_sed.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,8 @@
# If they are change the line below with the for loop to use the
# namespaced_rules

from __future__ import print_function

import subprocess


Expand Down Expand Up @@ -80,9 +82,9 @@

for rule in rules + unnamespaced_rules: #change me if using files with namespace tf set
full_cmd = cmd%locals()
print ("Running %s"%full_cmd)
print("Running {}".format(full_cmd))
ret_code = subprocess.call(full_cmd, shell=True)
if ret_code == 0:
print ("success")
print("success")
else:
print ("failure")
print("failure")
24 changes: 15 additions & 9 deletions tf/scripts/python_benchmark.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,13 +30,19 @@
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

from __future__ import print_function

import rostest
import rospy
import numpy
import unittest
import sys
import time
import StringIO
try:
from cStringIO import StringIO
except ImportError:
from io import StringIO


import tf.transformations
import geometry_msgs.msg
Expand All @@ -59,7 +65,7 @@ def mkm():
tm = tfMessage([mkm() for i in range(20)])

def deserel_to_string(o):
s = StringIO.StringIO()
s = StringIO()
o.serialize(s)
return s.getvalue()

Expand All @@ -70,7 +76,7 @@ def __init__(self, func):
self.func = func
def mean(self, iterations = 1000000):
started = time.time()
for i in xrange(iterations):
for i in range(iterations):
self.func()
took = time.time() - started
return took / iterations
Expand All @@ -81,28 +87,28 @@ def mean(self, iterations = 1000000):
m2 = t()
m2.deserialize(mstr)
for m in m2.transforms:
print type(m), sys.getrefcount(m)
print(type(m), sys.getrefcount(m))
assert deserel_to_string(m2) == mstr, "deserel screwed up for type %s" % repr(t)

m2 = t()
print "deserialize only ", 1e6 * Timer(lambda: m2.deserialize(mstr)).mean(), "us each"
print("deserialize only {} us each".format(1e6 * Timer(lambda: m2.deserialize(mstr)).mean())

sys.exit(0)

started = time.time()
for i in xrange(iterations):
for i in range(iterations):
for m in tm.transforms:
t.setTransform(m)
took = time.time() - started
print "setTransform only", iterations, "took", took, "%f us each" % (1e6 * took / iterations)
print("setTransform only {} took {} us each".format(iterations, took, (1e6 * took / iterations)))

started = time.time()
for i in xrange(iterations):
for i in range(iterations):
m2 = tfMessage()
m2.deserialize(mstr)
for m in m2.transforms:
t.setTransform(m)
took = time.time() - started
print "deserialize+setTransform ", iterations, "took", took, "%f us each" % (1e6 * took / iterations)
print("deserialize+setTransform {} took {} us each".format(iterations, took, (1e6 * took / iterations)))

from tf import TransformListener
11 changes: 6 additions & 5 deletions tf/scripts/tf_remap
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,8 @@

## remap a tf topic

from __future__ import print_function

import rospy
from tf.msg import tfMessage

Expand All @@ -43,12 +45,12 @@ class TfRemapper:
self.pub = rospy.Publisher('/tf', tfMessage, queue_size=1)
mappings = rospy.get_param('~mappings', [])
self.mappings = {}

for i in mappings:
if "old" in i and "new" in i:
self.mappings[i["old"]] = i["new"]

print "Applying the following mappings to incoming tf frame ids", self.mappings
print("Applying the following mappings to incoming tf frame ids", self.mappings)
rospy.Subscriber("/tf_old", tfMessage, self.callback)

def callback(self, tf_msg):
Expand All @@ -57,14 +59,13 @@ class TfRemapper:
transform.header.frame_id = self.mappings[transform.header.frame_id]
if transform.child_frame_id in self.mappings:
transform.child_frame_id = self.mappings[transform.child_frame_id]

self.pub.publish(tf_msg)

def remap_tf():

pub.publish(Empty())


if __name__ == '__main__':
rospy.init_node('tf_remapper')
tfr = TfRemapper()
Expand Down
45 changes: 19 additions & 26 deletions tf/scripts/view_frames
Original file line number Diff line number Diff line change
Expand Up @@ -33,10 +33,7 @@
#
# Revision $Id: gossipbot.py 1013 2008-05-21 01:08:56Z sfkwc $

## Simple demo of a rospy service client that calls a service to add
## two integers.

from __future__ import with_statement
from __future__ import print_function, with_statement

import sys, time
import os
Expand All @@ -54,59 +51,55 @@ import tf
def listen(duration):
rospy.init_node("view_frames", anonymous=True)
tf_listener = tf.TransformListener()
print "Listening to /tf for %f seconds"%duration
print("Listening to /tf for {} seconds".format(duration))
time.sleep(duration)
print "Done Listening"
print("Done Listening")
return tf_listener.allFramesAsDot(rospy.Time.now())


def poll(node_name):
print "Waiting for service %s/tf_frames"%node_name
rospy.wait_for_service('%s/tf_frames'%node_name)
print("Waiting for service {}/tf_frames".format(node_name))
rospy.wait_for_service('{}/tf_frames'.format(node_name))

try:
print "Polling service"
tf_frames_proxy = rospy.ServiceProxy('%s/tf_frames'%node_name, FrameGraph)

print("Polling service")
tf_frames_proxy = rospy.ServiceProxy('{}/tf_frames'.format(node_name), FrameGraph)
output = tf_frames_proxy.call(FrameGraphRequest())

except rospy.ServiceException, e:
print "Service call failed: %s"%e
except rospy.ServiceException as e:
print("Service call failed: {}".format(e))

return output.dot_graph

def generate(dot_graph):


with open('frames.gv', 'w') as outfile:
outfile.write(dot_graph)


try:
# Check version, make postscript if too old to make pdf
args = ["dot", "-V"]
try:
vstr = subprocess.Popen(args, stdout=subprocess.PIPE, stderr=subprocess.PIPE).communicate()[1]
except OSError, ex:
print "Warning: Could not execute `dot -V`. Is graphviz installed?"
except OSError as ex:
print("Warning: Could not execute `dot -V`. Is graphviz installed?")
sys.exit(-1)
v = distutils.version.StrictVersion('2.16')
r = re.compile(".*version (\d+\.?\d*)")
print vstr
print(vstr)
m = r.search(vstr)
if not m or not m.group(1):
print 'Warning: failed to determine your version of dot. Assuming v2.16'
print('Warning: failed to determine your version of dot. Assuming v2.16')
else:
version = distutils.version.StrictVersion(m.group(1))
print 'Detected dot version %s' % (version)
print('Detected dot version {}'.format(version))
if version > distutils.version.StrictVersion('2.8'):
subprocess.check_call(["dot", "-Tpdf", "frames.gv", "-o", "frames.pdf"])
print "frames.pdf generated"
print("frames.pdf generated")
else:
subprocess.check_call(["dot", "-Tps2", "frames.gv", "-o", "frames.ps"])
print "frames.ps generated"
print("frames.ps generated")
except subprocess.CalledProcessError:
print >> sys.stderr, "failed to generate frames.pdf"
print("failed to generate frames.pdf", file=sys.stderr)


if __name__ == '__main__':
Expand All @@ -120,7 +113,7 @@ if __name__ == '__main__':
if not options.node:
dot_graph = listen(5.0)
else:
print "Generating graph for node: ", options.node
print("Generating graph for node: ", options.node)
dot_graph = poll(options.node)

generate(dot_graph)
6 changes: 4 additions & 2 deletions tf/src/tf/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,8 @@
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

from __future__ import absolute_import

from tf2_ros import TransformException as Exception, ConnectivityException, LookupException, ExtrapolationException
from listener import Transformer, TransformListener, TransformerROS
from broadcaster import TransformBroadcaster
from .listener import Transformer, TransformListener, TransformerROS
from .broadcaster import TransformBroadcaster
4 changes: 2 additions & 2 deletions tf/src/tf/listener.py
Original file line number Diff line number Diff line change
Expand Up @@ -73,14 +73,14 @@ def waitForTransform(self, target_frame, source_frame, time, timeout, polling_sl
raise tf2_ros.TransformException("cannot wait for transform without a dedicated thread that listens to incoming TF messages")
can_transform, error_msg = self._buffer.can_transform(strip_leading_slash(target_frame), strip_leading_slash(source_frame), time, timeout, return_debug_tuple=True)
if not can_transform:
raise tf2_ros.TransformException(error_msg or "no such transformation: \"%s\" -> \"%s\"" % (source_frame, target_frame))
raise tf2_ros.TransformException(error_msg or "no such transformation: \"{}\" -> \"{}\"".format(source_frame, target_frame))

def waitForTransformFull(self, target_frame, target_time, source_frame, source_time, fixed_frame, timeout, polling_sleep_duration=None):
if not self._using_dedicated_thread:
raise tf2_ros.TransformException("cannot wait for transform without a dedicated thread that listens to incoming TF messages")
can_transform, error_msg = self._buffer.can_transform_full(strip_leading_slash(target_frame), target_time, strip_leading_slash(source_frame), source_time, strip_leading_slash(fixed_frame), timeout, return_debug_tuple=True)
if not can_transform:
raise tf2_ros.TransformException(error_msg or "no such transformation: \"%s\" -> \"%s\"" % (source_frame, target_frame))
raise tf2_ros.TransformException(error_msg or "no such transformation: \"{}\" -> \"{}\"".format(source_frame, target_frame))

def chain(self, target_frame, target_time, source_frame, source_time, fixed_frame):
return self._buffer._chain( target_frame, target_time, source_frame, source_time, fixed_frame)
Expand Down
29 changes: 14 additions & 15 deletions tf/src/tf/tfwtf.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,8 @@
#
# Revision $Id$

from __future__ import print_function

import time

from roswtf.rules import warning_rule, error_rule
Expand Down Expand Up @@ -63,8 +65,8 @@ def rostime_delta(ctx):
deltas[callerid] = secs

errors = []
for k, v in deltas.iteritems():
errors.append("receiving transform from [%s] that differed from ROS time by %ss"%(k, v))
for k, v in deltas.items():
errors.append("receiving transform from [{}] that differed from ROS time by {}s".format(k, v))
return errors

def reparenting(ctx):
Expand All @@ -75,7 +77,7 @@ def reparenting(ctx):
frame_id = t.child_frame_id
parent_id = t.header.frame_id
if frame_id in parent_id_map and parent_id_map[frame_id] != parent_id:
msg = "reparenting of [%s] to [%s] by [%s]"%(frame_id, parent_id, callerid)
msg = "reparenting of [{}] to [{}] by [{}]".format(frame_id, parent_id, callerid)
parent_id_map[frame_id] = parent_id
if msg not in errors:
errors.append(msg)
Expand Down Expand Up @@ -103,12 +105,11 @@ def cycle_detection(ctx):
try:
current_frame = parent_id_map[current_frame]
except KeyError:
break
break
if current_frame == frame:
errors.append("Frame %s is in a loop. It's loop has elements:\n%s"% (frame, " -> ".join(frame_list)))
errors.append("Frame {} is in a loop. It's loop has elements:\n{}".format(frame, " -> ".join(frame_list)))
break



return errors

def multiple_authority(ctx):
Expand All @@ -119,7 +120,7 @@ def multiple_authority(ctx):
frame_id = t.child_frame_id
parent_id = t.header.frame_id
if frame_id in authority_map and authority_map[frame_id] != callerid:
msg = "node [%s] publishing transform [%s] with parent [%s] already published by node [%s]"%(callerid, frame_id, parent_id, authority_map[frame_id])
msg = "node [{}] publishing transform [{}] with parent [{}] already published by node [{}]".format(callerid, frame_id, parent_id, authority_map[frame_id])
authority_map[frame_id] = callerid
if msg not in errors:
errors.append(msg)
Expand All @@ -137,14 +138,14 @@ def not_normalized(ctx):
q = t.transform.rotation
length = math.sqrt(q.x * q.x + q.y * q.y + q.z * q.z + q.w * q.w)
if math.fabs(length - 1) > 1e-6:
errors.append("rotation from [%s] to [%s] is not unit length, %f"%(t.header.frame_id, t.child_frame_id, length))
errors.append("rotation from [{}] to [{}] is not unit length, {}".format(t.header.frame_id, t.child_frame_id, length))
return errors

################################################################################
# roswtf PLUGIN

# tf_warnings and tf_errors declare the rules that we actually check

tf_warnings = [
(no_msgs, "No tf messages"),
(rostime_delta, "Received out-of-date/future transforms:"),
Expand Down Expand Up @@ -177,23 +178,21 @@ def roswtf_plugin_online(ctx):
# don't run plugin if tf isn't active as these checks take awhile
if not is_tf_active():
return
print "running tf checks, this will take a second..."

print("running tf checks, this will take a second...")
sub1 = rospy.Subscriber('/tf', tf.msg.tfMessage, _tf_handle)
time.sleep(1.0)
sub1.unregister()
print "... tf checks complete"
print("... tf checks complete")

for r in tf_warnings:
warning_rule(r, r[0](ctx), ctx)
for r in tf_errors:
error_rule(r, r[0](ctx), ctx)


# currently no static checks for tf
#def roswtf_plugin_static(ctx):
# for r in tf_warnings:
# warning_rule(r, r[0](ctx), ctx)
# for r in tf_errors:
# error_rule(r, r[0](ctx), ctx)

2 changes: 1 addition & 1 deletion tf/src/tf/transformations.py
Original file line number Diff line number Diff line change
Expand Up @@ -672,7 +672,7 @@ def shear_from_matrix(matrix):
l, V = numpy.linalg.eig(M33)
i = numpy.where(abs(numpy.real(l) - 1.0) < 1e-4)[0]
if len(i) < 2:
raise ValueError("No two linear independent eigenvectors found %s" % l)
raise ValueError("No two linear independent eigenvectors found {}".format(l))
V = numpy.real(V[:, i]).squeeze().T
lenorm = -1.0
for i0, i1 in ((0, 1), (0, 2), (1, 2)):
Expand Down
Loading