Skip to content

Commit

Permalink
Add in the linters for tf2_ros_py. (#740)
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette authored Dec 3, 2024
1 parent eaaa2d6 commit 84dd504
Show file tree
Hide file tree
Showing 16 changed files with 572 additions and 431 deletions.
2 changes: 1 addition & 1 deletion tf2_ros_py/doc/source/conf.py
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
# -- Project information -----------------------------------------------------

project = 'tf2_ros_py'
copyright = '2023, Open Source Robotics Foundation, Inc.'
copyright = '2023, Open Source Robotics Foundation, Inc.' # noqa: A001
author = 'Open Source Robotics Foundation, Inc.'

# The full version, including alpha/beta/rc tags
Expand Down
51 changes: 25 additions & 26 deletions tf2_ros_py/test/test_buffer.py
Original file line number Diff line number Diff line change
@@ -1,40 +1,39 @@
# Copyright 2019 Open Source Robotics Foundation, Inc.
# All rights reserved.
# Copyright (c) 2019 Open Source Robotics Foundation, 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:
# 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 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.
#
# 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 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 INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# * 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 copyright holder 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 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
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

from geometry_msgs.msg import TransformStamped
import pytest
import rclpy

from tf2_ros.buffer import Buffer
from geometry_msgs.msg import TransformStamped, PointStamped


class TestBuffer:

def build_transform(self, target, source, rclpy_time):
transform = TransformStamped()
transform.header.frame_id = target
Expand Down
78 changes: 40 additions & 38 deletions tf2_ros_py/test/test_buffer_client.py
Original file line number Diff line number Diff line change
@@ -1,46 +1,42 @@
# Copyright 2019 Open Source Robotics Foundation, Inc.
# All rights reserved.
# Copyright (c) 2019 Open Source Robotics Foundation, 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:
# 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 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.
#
# 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 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 INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# * 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 copyright holder 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 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
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

import pytest
import threading
import time

import rclpy

from tf2_ros.buffer_client import BufferClient
from geometry_msgs.msg import TransformStamped
from tf2_msgs.action import LookupTransform
from tf2_py import BufferCore, LookupException
import pytest
import rclpy
from rclpy.executors import SingleThreadedExecutor
from rclpy.time import Time
from tf2_msgs.action import LookupTransform
from tf2_msgs.msg import TF2Error
from tf2_py import BufferCore, LookupException
from tf2_ros.buffer_client import BufferClient


def build_transform(target_frame, source_frame, stamp):
Expand All @@ -61,8 +57,10 @@ def build_transform(target_frame, source_frame, stamp):


class MockBufferServer():

def __init__(self, node, buffer_core):
self.action_server = rclpy.action.ActionServer(node, LookupTransform, 'lookup_transform', self.execute_callback)
self.action_server = rclpy.action.ActionServer(
node, LookupTransform, 'lookup_transform', self.execute_callback)
self.buffer_core = buffer_core

def execute_callback(self, goal_handle):
Expand All @@ -72,9 +70,10 @@ def execute_callback(self, goal_handle):

try:
if not goal_handle.request.advanced:
transform = self.buffer_core.lookup_transform_core(target_frame=goal_handle.request.target_frame,
source_frame=goal_handle.request.source_frame,
time=Time.from_msg(goal_handle.request.source_time))
transform = self.buffer_core.lookup_transform_core(
target_frame=goal_handle.request.target_frame,
source_frame=goal_handle.request.source_frame,
time=Time.from_msg(goal_handle.request.source_time))
else:
transform = self.buffer_core.lookup_transform_full_core(
target_frame=goal_handle.request.target_frame,
Expand All @@ -85,7 +84,7 @@ def execute_callback(self, goal_handle):
)
response.transform = transform
goal_handle.succeed()
except LookupException as e:
except LookupException:
response.error.error = TF2Error.LOOKUP_ERROR
goal_handle.abort()

Expand All @@ -96,6 +95,7 @@ def destroy(self):


class TestBufferClient:

@classmethod
def setup_class(cls):
cls.context = rclpy.context.Context()
Expand Down Expand Up @@ -133,7 +133,8 @@ def spin(self):

def test_lookup_transform_true(self):
buffer_client = BufferClient(
self.node, 'lookup_transform', check_frequency=10.0, timeout_padding=rclpy.duration.Duration(seconds=0.0))
self.node, 'lookup_transform', check_frequency=10.0,
timeout_padding=rclpy.duration.Duration(seconds=0.0))

result = buffer_client.lookup_transform(
'foo', 'bar', rclpy.time.Time(), rclpy.duration.Duration(seconds=5.0))
Expand All @@ -144,7 +145,8 @@ def test_lookup_transform_true(self):

def test_lookup_transform_fail(self):
buffer_client = BufferClient(
self.node, 'lookup_transform', check_frequency=10.0, timeout_padding=rclpy.duration.Duration(seconds=0.0))
self.node, 'lookup_transform', check_frequency=10.0,
timeout_padding=rclpy.duration.Duration(seconds=0.0))

with pytest.raises(LookupException) as excinfo:
buffer_client.lookup_transform(
Expand Down
36 changes: 36 additions & 0 deletions tf2_ros_py/test/test_copyright.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
# Copyright (c) 2024 Open Source Robotics Foundation, 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 copyright holder 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 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
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

from ament_copyright.main import main
import pytest


@pytest.mark.copyright
@pytest.mark.linter
def test_copyright():
assert main(argv=['.', 'test']) == 0, 'Found errors'
39 changes: 39 additions & 0 deletions tf2_ros_py/test/test_flake8.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
# Copyright (c) 2024 Open Source Robotics Foundation, 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 copyright holder 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 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
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

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)
76 changes: 37 additions & 39 deletions tf2_ros_py/test/test_listener_and_broadcaster.py
Original file line number Diff line number Diff line change
@@ -1,43 +1,40 @@
# Copyright 2019 Open Source Robotics Foundation, Inc.
# All rights reserved.
# Copyright (c) 2019 Open Source Robotics Foundation, 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:
# 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 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.
#
# 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 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 INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# * 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 copyright holder 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 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
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

from geometry_msgs.msg import TransformStamped
import pytest
import rclpy

from geometry_msgs.msg import TransformStamped
from tf2_ros import ExtrapolationException
from tf2_ros.buffer import Buffer
from tf2_ros.transform_broadcaster import TransformBroadcaster
from tf2_ros.static_transform_broadcaster import StaticTransformBroadcaster
from tf2_ros.transform_listener import TransformListener
from tf2_ros.static_transform_listener import StaticTransformListener
from tf2_ros import ExtrapolationException
from tf2_ros.transform_broadcaster import TransformBroadcaster
from tf2_ros.transform_listener import TransformListener


def build_transform(target_frame, source_frame, stamp):
Expand All @@ -58,6 +55,7 @@ def build_transform(target_frame, source_frame, stamp):


class TestBroadcasterAndListener:

@classmethod
def setup_class(cls):
rclpy.init()
Expand Down Expand Up @@ -160,21 +158,21 @@ def test_broadcaster_and_listener(self):
assert broadcasted_transform == listened_transform_async

def test_static_broadcaster_and_listener(self):
broadcasted_transform = self.broadcast_static_transform(
broadcasted_tf = self.broadcast_static_transform(
target_frame='foo', source_frame='bar',
time_stamp=rclpy.time.Time(seconds=1.1, nanoseconds=0).to_msg())

listened_transform = self.buffer.lookup_transform(
listened_tf = self.buffer.lookup_transform(
target_frame='foo', source_frame='bar',
time=rclpy.time.Time(seconds=1.5, nanoseconds=0).to_msg())

assert broadcasted_transform.header.stamp.sec == 1
assert broadcasted_transform.header.stamp.nanosec == 100000000
assert broadcasted_tf.header.stamp.sec == 1
assert broadcasted_tf.header.stamp.nanosec == 100000000

assert listened_transform.header.stamp.sec == 1
assert listened_transform.header.stamp.nanosec == 500000000
assert listened_tf.header.stamp.sec == 1
assert listened_tf.header.stamp.nanosec == 500000000

assert broadcasted_transform.header.frame_id == listened_transform.header.frame_id
assert broadcasted_transform.child_frame_id == listened_transform.child_frame_id
assert broadcasted_transform.transform.translation == listened_transform.transform.translation
assert broadcasted_transform.transform.rotation == listened_transform.transform.rotation
assert broadcasted_tf.header.frame_id == listened_tf.header.frame_id
assert broadcasted_tf.child_frame_id == listened_tf.child_frame_id
assert broadcasted_tf.transform.translation == listened_tf.transform.translation
assert broadcasted_tf.transform.rotation == listened_tf.transform.rotation
Loading

0 comments on commit 84dd504

Please sign in to comment.