Skip to content

Commit

Permalink
Add in tests for tf2_tools. (#647)
Browse files Browse the repository at this point in the history
This just gives the python code the same tests that all
other python packages have.  To get there, we also had
to fix some style warnings.

Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette authored Jan 29, 2024
1 parent 542e8d4 commit bd73f76
Show file tree
Hide file tree
Showing 5 changed files with 109 additions and 30 deletions.
5 changes: 5 additions & 0 deletions tf2_tools/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,11 @@
<exec_depend>tf2_py</exec_depend>
<exec_depend>tf2_ros_py</exec_depend>

<test_depend>ament_copyright</test_depend>
<test_depend>ament_flake8</test_depend>
<test_depend>ament_pep257</test_depend>
<test_depend>python3-pytest</test_depend>

<export>
<build_type>ament_python</build_type>
</export>
Expand Down
23 changes: 23 additions & 0 deletions tf2_tools/test/test_copyright.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
# Copyright 2015 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from ament_copyright.main import main
import pytest


@pytest.mark.copyright
@pytest.mark.linter
def test_copyright():
rc = main(argv=['.', 'test'])
assert rc == 0, 'Found errors'
25 changes: 25 additions & 0 deletions tf2_tools/test/test_flake8.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
# Copyright 2017 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from ament_flake8.main import main_with_errors
import pytest


@pytest.mark.flake8
@pytest.mark.linter
def test_flake8():
rc, errors = main_with_errors(argv=[])
assert rc == 0, \
'Found %d code style errors / warnings:\n' % len(errors) + \
'\n'.join(errors)
23 changes: 23 additions & 0 deletions tf2_tools/test/test_pep257.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
# Copyright 2015 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from ament_pep257.main import main
import pytest


@pytest.mark.linter
@pytest.mark.pep257
def test_pep257():
rc = main(argv=['.', 'test'])
assert rc == 0, 'Found code style errors / warnings'
63 changes: 33 additions & 30 deletions tf2_tools/tf2_tools/view_frames.py
Original file line number Diff line number Diff line change
@@ -1,22 +1,23 @@
# Copyright (c) 2008, Willow Garage, Inc.
# All rights reserved.
# Copyright (c) 2008 Willow Garage Inc. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in the
# documentation and/or other materials provided with the distribution.
# * Neither the name of the Willow Garage, Inc. nor the names of its
# contributors may be used to endorse or promote products derived from
# this software without specific prior written permission.
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
#
# * Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in the
# documentation and/or other materials provided with the distribution.
#
# * Neither the name of the Willow Garage, Inc. nor the names of its
# contributors may be used to endorse or promote products derived from
# this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
Expand All @@ -32,12 +33,12 @@
import sys
import time

import yaml

import rclpy
from tf2_msgs.srv import FrameGraph
import tf2_ros

import yaml


def main():
rclpy.init(args=sys.argv)
Expand All @@ -48,13 +49,14 @@ def main():
parser.add_argument(
'--wait-time', '-t', type=float, default=5.0,
help='Listen to the /tf topic for this many seconds before rendering the frame tree')
parser.add_argument('-o','--output', help='Output filename')
parser.add_argument('-o', '--output', help='Output filename')
parsed_args = parser.parse_args(args=args_without_ros[1:])

node = rclpy.create_node('view_frames')

buf = tf2_ros.Buffer(node=node)
listener = tf2_ros.TransformListener(buf, node, spin_thread=False)
listener # To quiet a flake8 warning

executor = rclpy.executors.SingleThreadedExecutor()
executor.add_node(node)
Expand Down Expand Up @@ -82,21 +84,20 @@ def main():
except Exception as e:
node.get_logger().error('Service call failed %r' % (e,))
else:
node.get_logger().info(
'Result:'+ str(result) )
node.get_logger().info('Result:' + str(result))
data = yaml.safe_load(result.frame_yaml)

if parsed_args.output is not None:
frames_gv = '{:s}.gv'.format(parsed_args.output)
frames_pdf = '{:s}.pdf'.format(parsed_args.output)
else:
datetime = time.strftime('%Y-%m-%d_%H.%M.%S')
frames_gv = 'frames_{:s}.gv'.format(datetime)
frames_pdf = 'frames_{:s}.pdf'.format(datetime)

with open(frames_gv, 'w') as f:
f.write(generate_dot(data, node.get_clock().now().seconds_nanoseconds()))

cmd = ['dot', '-Tpdf', frames_gv, '-o', frames_pdf]
subprocess.Popen(cmd).communicate()
finally:
Expand All @@ -105,27 +106,29 @@ def main():
rclpy.shutdown()
return ret


def generate_dot(data, recorded_time):
if len(data) == 0:
return 'digraph G { "No tf data received" }'

dot = 'digraph G {\n'
for el in data:
map = data[el]
dot += '"'+map['parent']+'" -> "'+str(el)+'"'
data_map = data[el]
dot += '"' + data_map['parent'] + '" -> "' + str(el)+'"'
dot += '[label=" '
dot += 'Broadcaster: '+map['broadcaster']+'\\n'
dot += 'Average rate: '+str(map['rate'])+'\\n'
dot += 'Buffer length: '+str(map['buffer_length'])+'\\n'
dot += 'Most recent transform: '+str(map['most_recent_transform'])+'\\n'
dot += 'Oldest transform: '+str(map['oldest_transform'])+'\\n'
dot += 'Broadcaster: ' + data_map['broadcaster'] + '\\n'
dot += 'Average rate: ' + str(data_map['rate']) + '\\n'
dot += 'Buffer length: ' + str(data_map['buffer_length']) + '\\n'
dot += 'Most recent transform: ' + str(data_map['most_recent_transform']) + '\\n'
dot += 'Oldest transform: ' + str(data_map['oldest_transform']) + '\\n'
dot += '"];\n'
if not map['parent'] in data:
root = map['parent']
if not data_map['parent'] in data:
root = data_map['parent']
dot += 'edge [style=invis];\n'
dot += ' subgraph cluster_legend { style=bold; color=black; label ="view_frames Result";\n'
dot += '"Recorded at time: '+str(recorded_time[0]+recorded_time[1]/1e9)+'"[ shape=plaintext ] ;\n'
dot += '}->"'+root+'";\n}'
dot += '"Recorded at time: ' + str(recorded_time[0] + recorded_time[1] / 1e9) + \
'"[ shape=plaintext ] ;\n'
dot += '}->"' + root + '";\n}'
return dot


Expand Down

0 comments on commit bd73f76

Please sign in to comment.