Skip to content

Commit

Permalink
Added missing linting tests (#287)
Browse files Browse the repository at this point in the history
* fixed linting issues
* added missing python tests

Signed-off-by: Allison Thackston <[email protected]>
Signed-off-by: Allison Thackston <[email protected]>
  • Loading branch information
athackst authored and jacobperron committed Sep 8, 2020
1 parent 2d172e5 commit aa07f99
Show file tree
Hide file tree
Showing 13 changed files with 164 additions and 19 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,10 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from action_msgs.msg import GoalStatus
from example_interfaces.action import Fibonacci

import rclpy
from rclpy.action import ActionClient
from rclpy.callback_groups import ReentrantCallbackGroup
from rclpy.node import Node


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@

import rclpy
from rclpy.action import ActionClient
from rclpy.node import Node


def feedback_cb(logger, feedback):
Expand Down
24 changes: 24 additions & 0 deletions rclpy/actions/minimal_action_client/test/test_copyright.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
# 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_copyright.main import main
import pytest


@pytest.mark.copyright
@pytest.mark.linter
def test_copyright():
# Test is called from package root
rc = main(argv=['.'])
assert rc == 0, 'Found errors'
26 changes: 26 additions & 0 deletions rclpy/actions/minimal_action_client/test/test_flake8.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
# 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():
# Test is called from package root
rc, errors = main_with_errors(argv=['.'])
assert rc == 0, \
'Found %d code style errors / warnings:\n' % len(errors) + \
'\n'.join(errors)
24 changes: 24 additions & 0 deletions rclpy/actions/minimal_action_client/test/test_pep257.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
# 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_pep257.main import main
import pytest


@pytest.mark.linter
@pytest.mark.pep257
def test_pep257():
# Test is called from package root
rc = main(argv=['.'])
assert rc == 0, 'Found code style errors / warnings'
Original file line number Diff line number Diff line change
Expand Up @@ -42,18 +42,18 @@ def destroy(self):
super().destroy_node()

def goal_callback(self, goal_request):
"""Accepts or rejects a client request to begin an action."""
"""Accept or reject a client request to begin an action."""
# This server allows multiple goals in parallel
self.get_logger().info('Received goal request')
return GoalResponse.ACCEPT

def cancel_callback(self, goal_handle):
"""Accepts or rejects a client request to cancel an action."""
"""Accept or reject a client request to cancel an action."""
self.get_logger().info('Received cancel request')
return CancelResponse.ACCEPT

async def execute_callback(self, goal_handle):
"""Executes a goal."""
"""Execute a goal."""
self.get_logger().info('Executing goal...')

# Append the seeds for the Fibonacci sequence
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,18 +45,18 @@ def destroy(self):
super().destroy_node()

def goal_callback(self, goal_request):
"""Accepts or rejects a client request to begin an action."""
"""Accept or reject a client request to begin an action."""
self.get_logger().info('Received goal request')
return GoalResponse.ACCEPT

def handle_accepted_callback(self, goal_handle):
"""Provides a handle to an accepted goal."""
"""Provide a handle to an accepted goal."""
self.get_logger().info('Deferring execution...')
self._goal_handle = goal_handle
self._timer = self.create_timer(3.0, self.timer_callback)

def cancel_callback(self, goal_handle):
"""Accepts or rejects a client request to cancel an action."""
"""Accept or reject a client request to cancel an action."""
self.get_logger().info('Received cancel request')
return CancelResponse.ACCEPT

Expand All @@ -67,7 +67,7 @@ def timer_callback(self):
self._timer.cancel()

async def execute_callback(self, goal_handle):
"""Executes a goal."""
"""Execute a goal."""
self.get_logger().info('Executing goal...')

# Append the seeds for the Fibonacci sequence
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@
from rclpy.action import ActionServer, CancelResponse
from rclpy.callback_groups import ReentrantCallbackGroup
from rclpy.executors import MultiThreadedExecutor
from rclpy.node import Node


logger = None
Expand All @@ -32,7 +31,7 @@ def cancel_callback(goal_handle):


async def execute_callback(goal_handle):
"""Executes the goal."""
"""Execute the goal."""
logger.info('Executing goal...')

# Append the seeds for the fibonacci sequence
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ def destroy(self):
super().destroy_node()

def handle_accepted_callback(self, goal_handle):
"""Starts or defers execution of an already accepted goal."""
"""Start or defer execution of an already accepted goal."""
with self._goal_queue_lock:
if self._current_goal is not None:
# Put incoming goal in the queue
Expand All @@ -60,17 +60,17 @@ def handle_accepted_callback(self, goal_handle):
self._current_goal.execute()

def goal_callback(self, goal_request):
"""Accepts or rejects a client request to begin an action."""
"""Accept or reject a client request to begin an action."""
self.get_logger().info('Received goal request')
return GoalResponse.ACCEPT

def cancel_callback(self, goal_handle):
"""Accepts or rejects a client request to cancel an action."""
"""Accept or reject a client request to cancel an action."""
self.get_logger().info('Received cancel request')
return CancelResponse.ACCEPT

def execute_callback(self, goal_handle):
"""Executes a goal."""
"""Execute a goal."""
try:
self.get_logger().info('Executing goal...')

Expand Down Expand Up @@ -119,6 +119,7 @@ def execute_callback(self, goal_handle):
# No goal in the queue.
self._current_goal = None


def main(args=None):
rclpy.init(args=args)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ def destroy(self):
super().destroy_node()

def goal_callback(self, goal_request):
"""Accepts or rejects a client request to begin an action."""
"""Accept or reject a client request to begin an action."""
self.get_logger().info('Received goal request')
return GoalResponse.ACCEPT

Expand All @@ -62,12 +62,12 @@ def handle_accepted_callback(self, goal_handle):
goal_handle.execute()

def cancel_callback(self, goal):
"""Accepts or rejects a client request to cancel an action."""
"""Accept or reject a client request to cancel an action."""
self.get_logger().info('Received cancel request')
return CancelResponse.ACCEPT

def execute_callback(self, goal_handle):
"""Executes the goal."""
"""Execute the goal."""
self.get_logger().info('Executing goal...')

# Append the seeds for the Fibonacci sequence
Expand Down
24 changes: 24 additions & 0 deletions rclpy/actions/minimal_action_server/test/test_copyright.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
# 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_copyright.main import main
import pytest


@pytest.mark.copyright
@pytest.mark.linter
def test_copyright():
# Test is called from package root
rc = main(argv=['.'])
assert rc == 0, 'Found errors'
26 changes: 26 additions & 0 deletions rclpy/actions/minimal_action_server/test/test_flake8.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
# 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():
# Test is called from package root
rc, errors = main_with_errors(argv=['.'])
assert rc == 0, \
'Found %d code style errors / warnings:\n' % len(errors) + \
'\n'.join(errors)
24 changes: 24 additions & 0 deletions rclpy/actions/minimal_action_server/test/test_pep257.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
# 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_pep257.main import main
import pytest


@pytest.mark.linter
@pytest.mark.pep257
def test_pep257():
# Test is called from package root
rc = main(argv=['.'])
assert rc == 0, 'Found code style errors / warnings'

0 comments on commit aa07f99

Please sign in to comment.