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

Add None return to functions in the tests folder which do not return #1358

Merged
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
38 changes: 19 additions & 19 deletions rclpy/test/test_action_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@
TIME_FUDGE = 0.3


class MockActionServer():
class MockActionServer:

def __init__(self, node):
self.goal_srv = node.create_service(
Expand Down Expand Up @@ -82,7 +82,7 @@ def tearDownClass(cls):
cls.node.destroy_node()
rclpy.shutdown(context=cls.context)

def setUp(self):
def setUp(self) -> None:
self.feedback = None

def feedback_callback(self, feedback):
Expand All @@ -93,12 +93,12 @@ def timed_spin(self, duration):
while (time.time() - start_time) < duration:
rclpy.spin_once(self.node, executor=self.executor, timeout_sec=0.1)

def test_constructor_defaults(self):
def test_constructor_defaults(self) -> None:
# Defaults
ac = ActionClient(self.node, Fibonacci, 'fibonacci')
ac.destroy()

def test_constructor_no_defaults(self):
def test_constructor_no_defaults(self) -> None:
ac = ActionClient(
self.node,
Fibonacci,
Expand All @@ -111,7 +111,7 @@ def test_constructor_no_defaults(self):
)
ac.destroy()

def test_get_num_entities(self):
def test_get_num_entities(self) -> None:
ac = ActionClient(self.node, Fibonacci, 'fibonacci')
num_entities = ac.get_num_entities()
self.assertEqual(num_entities.num_subscriptions, 2)
Expand All @@ -121,7 +121,7 @@ def test_get_num_entities(self):
self.assertEqual(num_entities.num_services, 0)
ac.destroy()

def test_wait_for_server_nowait(self):
def test_wait_for_server_nowait(self) -> None:
ac = ActionClient(self.node, Fibonacci, 'not_fibonacci')
try:
start = time.monotonic()
Expand All @@ -132,7 +132,7 @@ def test_wait_for_server_nowait(self):
finally:
ac.destroy()

def test_wait_for_server_timeout(self):
def test_wait_for_server_timeout(self) -> None:
ac = ActionClient(self.node, Fibonacci, 'not_fibonacci')
try:
start = time.monotonic()
Expand All @@ -143,7 +143,7 @@ def test_wait_for_server_timeout(self):
finally:
ac.destroy()

def test_wait_for_server_exists(self):
def test_wait_for_server_exists(self) -> None:
ac = ActionClient(self.node, Fibonacci, 'fibonacci')
try:
start = time.monotonic()
Expand All @@ -154,7 +154,7 @@ def test_wait_for_server_exists(self):
finally:
ac.destroy()

def test_send_goal_async(self):
def test_send_goal_async(self) -> None:
ac = ActionClient(self.node, Fibonacci, 'fibonacci')
try:
self.assertTrue(ac.wait_for_server(timeout_sec=2.0))
Expand All @@ -166,7 +166,7 @@ def test_send_goal_async(self):
finally:
ac.destroy()

def test_send_goal_async_with_feedback_after_goal(self):
def test_send_goal_async_with_feedback_after_goal(self) -> None:
ac = ActionClient(self.node, Fibonacci, 'fibonacci')
try:
self.assertTrue(ac.wait_for_server(timeout_sec=2.0))
Expand All @@ -186,7 +186,7 @@ def test_send_goal_async_with_feedback_after_goal(self):
finally:
ac.destroy()

def test_send_goal_async_with_feedback_before_goal(self):
def test_send_goal_async_with_feedback_before_goal(self) -> None:
ac = ActionClient(self.node, Fibonacci, 'fibonacci')
try:
self.assertTrue(ac.wait_for_server(timeout_sec=2.0))
Expand All @@ -209,7 +209,7 @@ def test_send_goal_async_with_feedback_before_goal(self):
finally:
ac.destroy()

def test_send_goal_async_with_feedback_after_goal_result_requested(self):
def test_send_goal_async_with_feedback_after_goal_result_requested(self) -> None:
ac = ActionClient(self.node, Fibonacci, 'fibonacci')
try:
self.assertTrue(ac.wait_for_server(timeout_sec=2.0))
Expand All @@ -235,7 +235,7 @@ def test_send_goal_async_with_feedback_after_goal_result_requested(self):
finally:
ac.destroy()

def test_send_goal_async_with_feedback_for_another_goal(self):
def test_send_goal_async_with_feedback_for_another_goal(self) -> None:
ac = ActionClient(self.node, Fibonacci, 'fibonacci')
try:
self.assertTrue(ac.wait_for_server(timeout_sec=2.0))
Expand Down Expand Up @@ -266,7 +266,7 @@ def test_send_goal_async_with_feedback_for_another_goal(self):
finally:
ac.destroy()

def test_send_goal_async_with_feedback_for_not_a_goal(self):
def test_send_goal_async_with_feedback_for_not_a_goal(self) -> None:
ac = ActionClient(self.node, Fibonacci, 'fibonacci')
try:
self.assertTrue(ac.wait_for_server(timeout_sec=2.0))
Expand All @@ -286,7 +286,7 @@ def test_send_goal_async_with_feedback_for_not_a_goal(self):
finally:
ac.destroy()

def test_send_goal_multiple(self):
def test_send_goal_multiple(self) -> None:
ac = ActionClient(
self.node,
Fibonacci,
Expand All @@ -310,7 +310,7 @@ def test_send_goal_multiple(self):
finally:
ac.destroy()

def test_send_goal_async_no_server(self):
def test_send_goal_async_no_server(self) -> None:
ac = ActionClient(self.node, Fibonacci, 'not_fibonacci')
try:
future = ac.send_goal_async(Fibonacci.Goal())
Expand All @@ -319,7 +319,7 @@ def test_send_goal_async_no_server(self):
finally:
ac.destroy()

def test_send_cancel_async(self):
def test_send_cancel_async(self) -> None:
ac = ActionClient(self.node, Fibonacci, 'fibonacci')
try:
self.assertTrue(ac.wait_for_server(timeout_sec=2.0))
Expand All @@ -340,7 +340,7 @@ def test_send_cancel_async(self):
finally:
ac.destroy()

def test_get_result_async(self):
def test_get_result_async(self) -> None:
ac = ActionClient(self.node, Fibonacci, 'fibonacci')
try:
self.assertTrue(ac.wait_for_server(timeout_sec=2.0))
Expand All @@ -358,7 +358,7 @@ def test_get_result_async(self):
finally:
ac.destroy()

def test_different_type_raises(self):
def test_different_type_raises(self) -> None:
ac = ActionClient(self.node, Fibonacci, 'fibonacci')
try:
with self.assertRaises(TypeError):
Expand Down
6 changes: 3 additions & 3 deletions rclpy/test/test_action_graph.py
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ def get_names_and_types(
end = time.monotonic()
assert len(nat) == expected_num_names

def test_get_action_client_names_and_types_by_node(self):
def test_get_action_client_names_and_types_by_node(self) -> None:
self.get_names_and_types(
get_action_client_names_and_types_by_node,
self.node1,
Expand Down Expand Up @@ -128,7 +128,7 @@ def test_get_action_client_names_and_types_by_node(self):
assert TEST_NAMESPACE2 + '/' + TEST_ACTION0 in [name20, name21]
assert TEST_NAMESPACE2 + '/' + TEST_ACTION1 in [name20, name21]

def test_get_action_server_names_and_types_by_node(self):
def test_get_action_server_names_and_types_by_node(self) -> None:
self.get_names_and_types(
get_action_server_names_and_types_by_node,
self.node1,
Expand Down Expand Up @@ -170,7 +170,7 @@ def test_get_action_server_names_and_types_by_node(self):
assert TEST_NAMESPACE2 + '/' + TEST_ACTION0 in [name20, name21]
assert TEST_NAMESPACE2 + '/' + TEST_ACTION1 in [name20, name21]

def test_get_action_names_and_types(self):
def test_get_action_names_and_types(self) -> None:
names_and_types = self.get_names_and_types(
get_action_names_and_types,
self.node0,
Expand Down
Loading